ros2_control - foxy
Loading...
Searching...
No Matches
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.h"
46#include "realtime_tools/realtime_publisher.h"
47
48#include "control_toolbox/pid.hpp"
49#include "control_toolbox/visibility_control.hpp"
50
51namespace control_toolbox
52{
53
54class CONTROL_TOOLBOX_PUBLIC PidROS
55{
56public:
66 template <class NodeT>
67 explicit PidROS(std::shared_ptr<NodeT> node_ptr, std::string topic_prefix = std::string(""))
68 : PidROS(
69 node_ptr->get_node_base_interface(), node_ptr->get_node_logging_interface(),
70 node_ptr->get_node_parameters_interface(), node_ptr->get_node_topics_interface(),
71 topic_prefix)
72 {
73 }
74
75 PidROS(
76 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
77 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
78 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
79 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
80 std::string topic_prefix = std::string(""))
81 : node_base_(node_base),
82 node_logging_(node_logging),
83 node_params_(node_params),
84 topics_interface_(topics_interface)
85 {
86 initialize(topic_prefix);
87 }
88
98 void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup);
99
104 bool initPid();
105
109 void reset();
110
121 double computeCommand(double error, rclcpp::Duration dt);
122
134 double computeCommand(double error, double error_dot, rclcpp::Duration dt);
135
140 Pid::Gains getGains();
141
151 void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
152
157 void setGains(const Pid::Gains & gains);
158
163 void setCurrentCmd(double cmd);
164
169 double getCurrentCmd();
170
175 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> getPidStatePublisher();
176
183 void getCurrentPIDErrors(double & pe, double & ie, double & de);
184
188 void printValues();
189
194 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
196 {
197 return parameter_callback_;
198 }
199
200private:
201 void setParameterEventCallback();
202
203 void publishPIDState(double cmd, double error, rclcpp::Duration dt);
204
205 void declareParam(const std::string & param_name, rclcpp::ParameterValue param_value);
206
207 bool getDoubleParam(const std::string & param_name, double & value);
208
209 bool getBooleanParam(const std::string & param_name, bool & value);
210
211 void initialize(std::string topic_prefix);
212
213 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
214
215 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
216 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
217 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
218 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;
219
220 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
221 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;
222
223 Pid pid_;
224 std::string topic_prefix_;
225 std::string param_prefix_;
226};
227
228} // namespace control_toolbox
229
230#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:195
PidROS(std::shared_ptr< NodeT > node_ptr, std::string topic_prefix=std::string(""))
Constructor of PidROS class.
Definition pid_ros.hpp:67
A basic pid class.
Definition pid.hpp:109
Definition dither.hpp:46