ros2_control - rolling
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.hpp"
46#include "realtime_tools/realtime_publisher.hpp"
47
48#include "control_toolbox/pid.hpp"
49
50namespace control_toolbox
51{
52
53class PidROS
54{
55public:
71 template <class NodeT>
72 explicit PidROS(
73 std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix,
74 const std::string & topic_prefix)
75 : PidROS(
79 {
80 }
81
96 template <class NodeT>
106
118 PidROS(
119 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
120 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
121 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
122 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
123 const std::string & param_prefix, const std::string & topic_prefix,
125
143 double p, double i, double d, double u_max, double u_min,
145
152
158 void reset();
159
165 void reset(bool save_i_term);
166
177 double compute_command(double error, const rclcpp::Duration & dt);
178
190 double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
191
199
216 bool set_gains(
217 double p, double i, double d, double u_max, double u_min,
219
228 bool set_gains(const Pid::Gains & gains);
229
234 void set_current_cmd(double cmd);
235
240 double get_current_cmd();
241
246 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> get_pid_state_publisher();
247
254 void get_current_pid_errors(double & pe, double & ie, double & de);
255
259 void print_values();
260
265 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
267 {
268 return parameter_callback_;
269 }
270
271protected:
272 std::string topic_prefix_;
273 std::string param_prefix_;
274
275private:
276 void set_parameter_event_callback();
277
278 void publish_pid_state(double cmd, double error, rclcpp::Duration dt);
279
280 void declare_param(const std::string & param_name, rclcpp::ParameterValue param_value);
281
282 bool get_double_param(const std::string & param_name, double & value);
283
284 bool get_boolean_param(const std::string & param_name, bool & value);
285
286 bool get_string_param(const std::string & param_name, std::string & value);
287
288 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
289
290 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
291 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
292 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
293 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;
294
295 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
296 control_msgs::msg::PidState pid_state_msg_;
297 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;
298
299 Pid pid_;
300};
301
302} // namespace control_toolbox
303
304#endif // CONTROL_TOOLBOX__PID_ROS_HPP_
A Low-pass filter class.
Definition low_pass_filter.hpp:79
Definition pid_ros.hpp:54
void print_values()
Print to console the current parameters.
Definition pid_ros.cpp:400
bool initialize_from_ros_parameters()
Initialize the PID controller based on already set parameters.
Definition pid_ros.cpp:161
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:72
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid_ros.cpp:387
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid_ros.cpp:391
double get_current_cmd()
Return current command for this PID controller.
Definition pid_ros.cpp:389
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:303
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:319
PidROS(std::shared_ptr< NodeT > node_ptr, std::string param_prefix, std::string topic_prefix, bool activate_state_publisher)
Constructor of PidROS class.
Definition pid_ros.hpp:97
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:234
Pid::Gains get_gains()
Get PID gains for the controller.
Definition pid_ros.cpp:317
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr get_parameters_callback_handle()
Return PID parameters callback handle.
Definition pid_ros.hpp:266
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > get_pid_state_publisher()
Return PID state publisher.
Definition pid_ros.cpp:298
void reset()
Reset the state of this PID controller.
Definition pid_ros.cpp:289
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:255
Definition dither.hpp:46
Antiwindup strategy for PID controllers.
Definition pid.hpp:67
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:261