ros2_control - rolling
Loading...
Searching...
No Matches
pid_ros.hpp
1// Copyright (c) 2020, Open Source Robotics Foundation, Inc.
2//
3// Redistribution and use in source and binary forms, with or without
4// modification, are permitted provided that the following conditions are met:
5//
6// * Redistributions of source code must retain the above copyright
7// notice, this list of conditions and the following disclaimer.
8//
9// * Redistributions in binary form must reproduce the above copyright
10// notice, this list of conditions and the following disclaimer in the
11// documentation and/or other materials provided with the distribution.
12//
13// * Neither the name of the Willow Garage nor the names of its
14// contributors may be used to endorse or promote products derived from
15// this software without specific prior written permission.
16//
17// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27// POSSIBILITY OF SUCH DAMAGE.
28
29#ifndef CONTROL_TOOLBOX__PID_ROS_HPP_
30#define CONTROL_TOOLBOX__PID_ROS_HPP_
31
32#include <memory>
33#include <string>
34
35#include "control_msgs/msg/pid_state.hpp"
36
37#include "rclcpp/clock.hpp"
38#include "rclcpp/duration.hpp"
39#include "rclcpp/node.hpp"
40
41#include "realtime_tools/realtime_buffer.hpp"
42#include "realtime_tools/realtime_publisher.hpp"
43
44#include "control_toolbox/pid.hpp"
45
46namespace control_toolbox
47{
48
49class PidROS
50{
51public:
67 template <class NodeT>
68 explicit PidROS(
69 std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix,
70 const std::string & topic_prefix)
71 : PidROS(
72 node_ptr->get_node_base_interface(), node_ptr->get_node_logging_interface(),
73 node_ptr->get_node_parameters_interface(), node_ptr->get_node_topics_interface(),
74 param_prefix, topic_prefix, !topic_prefix.empty())
75 {
76 }
77
92 template <class NodeT>
93 explicit PidROS(
94 std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix,
95 const std::string & topic_prefix, bool activate_state_publisher)
96 : PidROS(
97 node_ptr->get_node_base_interface(), node_ptr->get_node_logging_interface(),
98 node_ptr->get_node_parameters_interface(), node_ptr->get_node_topics_interface(),
99 param_prefix, topic_prefix, activate_state_publisher)
100 {
101 }
102
114 PidROS(
115 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
116 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
117 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
118 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
119 const std::string & param_prefix, const std::string & topic_prefix,
120 bool activate_state_publisher);
121
139 double p, double i, double d, double u_max, double u_min,
140 const AntiWindupStrategy & antiwindup_strat, bool save_i_term);
141
148
154 void reset();
155
161 void reset(bool save_i_term);
162
173 double compute_command(double error, const rclcpp::Duration & dt);
174
186 double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
187
195
212 bool set_gains(
213 double p, double i, double d, double u_max, double u_min,
214 const AntiWindupStrategy & antiwindup_strat);
215
224 bool set_gains(const Pid::Gains & gains);
225
230 void set_current_cmd(double cmd);
231
236 double get_current_cmd();
237
242 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> get_pid_state_publisher();
243
250 void get_current_pid_errors(double & pe, double & ie, double & de);
251
255 void print_values();
256
261 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
263 {
264 return parameter_callback_;
265 }
266
267protected:
268 std::string topic_prefix_;
269 std::string param_prefix_;
270
271private:
272 void set_parameter_event_callback();
273
274 void publish_pid_state(double cmd, double error, rclcpp::Duration dt);
275
276 void declare_param(const std::string & param_name, rclcpp::ParameterValue param_value);
277
278 bool get_double_param(const std::string & param_name, double & value);
279
280 bool get_boolean_param(const std::string & param_name, bool & value);
281
282 bool get_string_param(const std::string & param_name, std::string & value);
283
284 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
285
286 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
287 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
288 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
289 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;
290
291 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
292 control_msgs::msg::PidState pid_state_msg_;
293 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;
294
295 Pid pid_;
296};
297
298} // namespace control_toolbox
299
300#endif // CONTROL_TOOLBOX__PID_ROS_HPP_
Definition pid_ros.hpp:50
void print_values()
Print to console the current parameters.
Definition pid_ros.cpp:396
bool initialize_from_ros_parameters()
Initialize the PID controller based on already set parameters.
Definition pid_ros.cpp:157
PidROS(std::shared_ptr< NodeT > node_ptr, const std::string &param_prefix, const std::string &topic_prefix)
Constructor of PidROS class.
Definition pid_ros.hpp:68
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid_ros.cpp:383
PidROS(std::shared_ptr< NodeT > node_ptr, const std::string &param_prefix, const std::string &topic_prefix, bool activate_state_publisher)
Constructor of PidROS class.
Definition pid_ros.hpp:93
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid_ros.cpp:387
double get_current_cmd()
Return current command for this PID controller.
Definition pid_ros.cpp:385
double compute_command(double error, const rclcpp::Duration &dt)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is...
Definition pid_ros.cpp:299
bool set_gains(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat)
Set PID gains for the controller.
Definition pid_ros.cpp:315
bool initialize_from_args(double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat, bool save_i_term)
Initialize the PID controller and set the parameters.
Definition pid_ros.cpp:230
Pid::Gains get_gains()
Get PID gains for the controller.
Definition pid_ros.cpp:313
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr get_parameters_callback_handle()
Return PID parameters callback handle.
Definition pid_ros.hpp:262
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > get_pid_state_publisher()
Return PID state publisher.
Definition pid_ros.cpp:294
void reset()
Reset the state of this PID controller.
Definition pid_ros.cpp:285
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:262
Definition dither.hpp:42
Antiwindup strategy for PID controllers.
Definition pid.hpp:63
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:268