ros2_control - rolling
pid_ros.hpp
1 // Copyright (c) 2020, Open Source Robotics Foundation, Inc.
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of the Willow Garage nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 #ifndef CONTROL_TOOLBOX__PID_ROS_HPP_
34 #define CONTROL_TOOLBOX__PID_ROS_HPP_
35 
36 #include <memory>
37 #include <string>
38 
39 #include "control_msgs/msg/pid_state.hpp"
40 
41 #include "rclcpp/clock.hpp"
42 #include "rclcpp/duration.hpp"
43 #include "rclcpp/node.hpp"
44 
45 #include "realtime_tools/realtime_buffer.hpp"
46 #include "realtime_tools/realtime_publisher.hpp"
47 
48 #include "control_toolbox/pid.hpp"
49 #include "control_toolbox/visibility_control.hpp"
50 
51 namespace control_toolbox
52 {
53 
54 class CONTROL_TOOLBOX_PUBLIC PidROS
55 {
56 public:
71  template<class NodeT>
72  explicit PidROS(
73  std::shared_ptr<NodeT> node_ptr,
74  std::string prefix = std::string(""),
75  bool prefix_is_for_params = false
76  )
77  : PidROS(
78  node_ptr->get_node_base_interface(),
79  node_ptr->get_node_logging_interface(),
80  node_ptr->get_node_parameters_interface(),
81  node_ptr->get_node_topics_interface(),
82  prefix, prefix_is_for_params)
83  {
84  }
85 
86  PidROS(
87  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
88  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
89  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
90  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
91  std::string prefix = std::string(""), bool prefix_is_for_params = false);
92 
104  void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup);
105 
110  bool initPid();
111 
115  void reset();
116 
127  double computeCommand(double error, rclcpp::Duration dt);
128 
140  double computeCommand(double error, double error_dot, rclcpp::Duration dt);
141 
146  Pid::Gains getGains();
147 
159  void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
160 
167  void setGains(const Pid::Gains & gains);
168 
173  void setCurrentCmd(double cmd);
174 
179  double getCurrentCmd();
180 
185  std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> getPidStatePublisher();
186 
193  void getCurrentPIDErrors(double & pe, double & ie, double & de);
194 
198  void printValues();
199 
204  inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
206  {
207  return parameter_callback_;
208  }
209 
210 protected:
211  std::string topic_prefix_;
212  std::string param_prefix_;
213 
214 private:
215  void setParameterEventCallback();
216 
217  void publishPIDState(double cmd, double error, rclcpp::Duration dt);
218 
219  void declareParam(const std::string & param_name, rclcpp::ParameterValue param_value);
220 
221  bool getDoubleParam(const std::string & param_name, double & value);
222 
223  bool getBooleanParam(const std::string & param_name, bool & value);
224 
231  void initialize(std::string topic_prefix);
232 
233  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
234 
235  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
236  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
237  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
238  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;
239 
240  std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
241  std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;
242 
243  Pid pid_;
244 };
245 
246 } // namespace control_toolbox
247 
248 #endif // CONTROL_TOOLBOX__PID_ROS_HPP_
Definition: pid_ros.hpp:55
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr getParametersCallbackHandle()
Return PID parameters callback handle.
Definition: pid_ros.hpp:205
PidROS(std::shared_ptr< NodeT > node_ptr, std::string prefix=std::string(""), bool prefix_is_for_params=false)
Constructor of PidROS class.
Definition: pid_ros.hpp:72
A basic pid class.
Definition: pid.hpp:106
Definition: dither.hpp:46
Store gains in a struct to allow easier realtime buffer usage.
Definition: pid.hpp:112