ros2_control - iron
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:
70 template <class NodeT>
71 [[deprecated("Use overloads with explicit prefixes for params and topics")]] explicit PidROS(
72 std::shared_ptr<NodeT> node_ptr, std::string prefix = std::string(""),
73 bool prefix_is_for_params = false)
74 : PidROS(
78 {
79 }
80
96 template <class NodeT>
97 explicit PidROS(
98 std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix,
99 const std::string & topic_prefix)
100 : PidROS(
104 {
105 }
120 template <class NodeT>
130
131 [[deprecated("Use overloads with explicit prefixes for params and topics")]] PidROS(
132 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
133 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
134 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
135 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
136 std::string prefix = std::string(""), bool prefix_is_for_params = false);
137
149 PidROS(
150 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
151 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
152 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
153 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
154 const std::string & param_prefix, const std::string & topic_prefix,
156
172 [[deprecated("Use initialize_from_args with AntiWindupStrategy instead.")]]
174 double p, double i, double d, double i_max, double i_min, bool antiwindup);
175
189 [[deprecated("Use initialize_from_args() instead")]] void initPid(
190 double p, double i, double d, double i_max, double i_min, bool antiwindup);
191
208 [[deprecated("Use initialize_from_args with AntiWindupStrategy instead.")]]
210 double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term);
211
224 [[deprecated("Use initialize_from_args() instead")]] void initPid(
225 double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term);
226
244 double p, double i, double d, double u_max, double u_min,
246
253
258 [[deprecated("Use initialize_from_ros_parameters() instead")]] bool initPid();
259
265 void reset();
266
272 void reset(bool save_i_term);
273
284 double compute_command(double error, const rclcpp::Duration & dt);
285
296 [[deprecated("Use compute_command() instead")]] double computeCommand(
297 double error, rclcpp::Duration dt);
298
310 double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
311
323 [[deprecated("Use compute_command() instead")]] double computeCommand(
324 double error, double error_dot, rclcpp::Duration dt);
325
333
338 [[deprecated("Use get_gains() instead")]] Pid::Gains getGains();
339
356 [[deprecated("Use set_gains with AntiWindupStrategy instead.")]]
357 bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
358
375 bool set_gains(
376 double p, double i, double d, double u_max, double u_min,
378
393 [[deprecated("Use set_gains() instead")]] void setGains(
394 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
395
404 bool set_gains(const Pid::Gains & gains);
405
412 [[deprecated("Use set_gains() instead")]] void setGains(const Pid::Gains & gains);
413
418 void set_current_cmd(double cmd);
419
424 [[deprecated("Use set_current_cmd() instead")]] void setCurrentCmd(double cmd);
425
430 double get_current_cmd();
431
436 [[deprecated("Use get_current_cmd() instead")]] double getCurrentCmd();
437
442 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> get_pid_state_publisher();
443
448 [[deprecated("Use get_pid_state_publisher() instead")]]
449 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> getPidStatePublisher();
450
457 void get_current_pid_errors(double & pe, double & ie, double & de);
458
465 [[deprecated("Use get_current_pid_errors() instead")]] void getCurrentPIDErrors(
466 double & pe, double & ie, double & de);
467
471 void print_values();
472
476 [[deprecated("Use print_values() instead")]] void printValues();
477
482 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
484 {
485 return parameter_callback_;
486 }
487
492 [[deprecated("Use get_parameters_callback_handle() instead")]]
493 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
498
499protected:
500 std::string topic_prefix_;
501 std::string param_prefix_;
502
503private:
504 // DEPRECATION START
505 // this was added to avoid ABI breaks
506 [[deprecated]] void setParameterEventCallback();
507
508 [[deprecated]] void publishPIDState(double cmd, double error, rclcpp::Duration dt);
509
510 [[deprecated]] void declareParam(
511 const std::string & param_name, rclcpp::ParameterValue param_value);
512
513 [[deprecated]] bool getDoubleParam(const std::string & param_name, double & value);
514
515 [[deprecated]] bool getBooleanParam(const std::string & param_name, bool & value);
516
523 [[deprecated]] void initialize(std::string topic_prefix);
524 // DEPRECATED END
525
526 void set_parameter_event_callback();
527
528 void publish_pid_state(double cmd, double error, rclcpp::Duration dt);
529
530 void declare_param(const std::string & param_name, rclcpp::ParameterValue param_value);
531
532 bool get_double_param(const std::string & param_name, double & value);
533
534 bool get_boolean_param(const std::string & param_name, bool & value);
535
536 bool get_string_param(const std::string & param_name, std::string & value);
537
545 [[deprecated]] void set_prefixes(const std::string & topic_prefix);
546
547 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
548
549 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
550 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
551 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
552 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;
553
554 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
555 control_msgs::msg::PidState pid_state_msg_;
556 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;
557
558 Pid pid_;
559};
560
561} // namespace control_toolbox
562
563#endif // CONTROL_TOOLBOX__PID_ROS_HPP_
A Low-pass filter class.
Definition low_pass_filter.hpp:78
Definition pid_ros.hpp:54
void print_values()
Print to console the current parameters.
Definition pid_ros.cpp:545
bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Set PID gains for the controller.
Definition pid_ros.cpp:449
bool initialize_from_ros_parameters()
Initialize the PID controller based on already set parameters.
Definition pid_ros.cpp:255
void setCurrentCmd(double cmd)
Set current command for this PID controller.
Definition pid_ros.cpp:767
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr getParametersCallbackHandle()
Return PID parameters callback handle.
Definition pid_ros.hpp:494
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:97
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid_ros.cpp:776
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid_ros.cpp:532
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:121
double computeCommand(double error, 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:745
double getCurrentCmd()
Return current command for this PID controller.
Definition pid_ros.cpp:769
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid_ros.cpp:536
double get_current_cmd()
Return current command for this PID controller.
Definition pid_ros.cpp:534
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > getPidStatePublisher()
Return PID state publisher.
Definition pid_ros.cpp:771
bool initPid()
Initialize the PID controller based on already set parameters.
Definition pid_ros.cpp:743
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:71
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:433
void printValues()
Print to console the current parameters.
Definition pid_ros.cpp:781
bool initialize_from_args(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Initialize the PID controller and set the parameters.
Definition pid_ros.cpp:336
void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
Set PID gains for the controller.
Definition pid_ros.cpp:760
Pid::Gains getGains()
Get PID gains for the controller.
Definition pid_ros.cpp:759
Pid::Gains get_gains()
Get PID gains for the controller.
Definition pid_ros.cpp:447
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr get_parameters_callback_handle()
Return PID parameters callback handle.
Definition pid_ros.hpp:483
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > get_pid_state_publisher()
Return PID state publisher.
Definition pid_ros.cpp:428
void reset()
Reset the state of this PID controller.
Definition pid_ros.cpp:419
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:284
Definition dither.hpp:46
Antiwindup strategy for PID controllers.
Definition pid.hpp:72
Store gains in a struct to allow easier realtime box usage.
Definition pid.hpp:290