ros2_control - jazzy
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 template <class NodeT>
81 explicit PidROS(std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix)
82 : PidROS(
86 {
87 }
99 template <class NodeT>
100 explicit PidROS(
101 std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix,
102 const std::string & topic_prefix)
103 : PidROS(
107 {
108 }
121 template <class NodeT>
131
132 [[deprecated("Use overloads with explicit prefixes for params and topics")]] PidROS(
133 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
134 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
135 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
136 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
137 std::string prefix = std::string(""), bool prefix_is_for_params = false);
138
150 PidROS(
151 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
152 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
153 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
154 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
155 const std::string & param_prefix, const std::string & topic_prefix,
157
173 [[deprecated("Use initialize_from_args with AntiWindupStrategy instead.")]]
175 double p, double i, double d, double i_max, double i_min, bool antiwindup);
176
190 [[deprecated("Use initialize_from_args() instead")]] void initPid(
191 double p, double i, double d, double i_max, double i_min, bool antiwindup);
192
209 [[deprecated("Use initialize_from_args with AntiWindupStrategy instead.")]]
211 double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term);
212
225 [[deprecated("Use initialize_from_args() instead")]] void initPid(
226 double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term);
227
245 double p, double i, double d, double u_max, double u_min,
247
254
259 [[deprecated("Use initialize_from_ros_parameters() instead")]] bool initPid();
260
266 void reset();
267
273 void reset(bool save_i_term);
274
285 double compute_command(double error, const rclcpp::Duration & dt);
286
297 [[deprecated("Use compute_command() instead")]] double computeCommand(
298 double error, rclcpp::Duration dt);
299
311 double compute_command(double error, double error_dot, const rclcpp::Duration & dt);
312
324 [[deprecated("Use compute_command() instead")]] double computeCommand(
325 double error, double error_dot, rclcpp::Duration dt);
326
334
339 [[deprecated("Use get_gains() instead")]] Pid::Gains getGains();
340
357 [[deprecated("Use set_gains with AntiWindupStrategy instead.")]]
358 bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
359
376 bool set_gains(
377 double p, double i, double d, double u_max, double u_min,
379
394 [[deprecated("Use set_gains() instead")]] void setGains(
395 double p, double i, double d, double i_max, double i_min, bool antiwindup = false);
396
405 bool set_gains(const Pid::Gains & gains);
406
413 [[deprecated("Use set_gains() instead")]] void setGains(const Pid::Gains & gains);
414
419 void set_current_cmd(double cmd);
420
425 [[deprecated("Use set_current_cmd() instead")]] void setCurrentCmd(double cmd);
426
431 double get_current_cmd();
432
437 [[deprecated("Use get_current_cmd() instead")]] double getCurrentCmd();
438
443 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> get_pid_state_publisher();
444
449 [[deprecated("Use get_pid_state_publisher() instead")]]
450 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> getPidStatePublisher();
451
458 void get_current_pid_errors(double & pe, double & ie, double & de);
459
466 [[deprecated("Use get_current_pid_errors() instead")]] void getCurrentPIDErrors(
467 double & pe, double & ie, double & de);
468
472 void print_values();
473
477 [[deprecated("Use print_values() instead")]] void printValues();
478
483 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
485 {
486 return parameter_callback_;
487 }
488
493 [[deprecated("Use get_parameters_callback_handle() instead")]]
494 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
499
500protected:
501 std::string topic_prefix_;
502 std::string param_prefix_;
503
504private:
505 // DEPRECATION START
506 // this was added to avoid ABI breaks
507 [[deprecated]] void setParameterEventCallback();
508
509 [[deprecated]] void publishPIDState(double cmd, double error, rclcpp::Duration dt);
510
511 [[deprecated]] void declareParam(
512 const std::string & param_name, rclcpp::ParameterValue param_value);
513
514 [[deprecated]] bool getDoubleParam(const std::string & param_name, double & value);
515
516 [[deprecated]] bool getBooleanParam(const std::string & param_name, bool & value);
517
524 [[deprecated]] void initialize(std::string topic_prefix);
525 // DEPRECATED END
526
527 void set_parameter_event_callback();
528
529 void publish_pid_state(double cmd, double error, rclcpp::Duration dt);
530
531 void declare_param(const std::string & param_name, rclcpp::ParameterValue param_value);
532
533 bool get_double_param(const std::string & param_name, double & value);
534
535 bool get_boolean_param(const std::string & param_name, bool & value);
536
537 bool get_string_param(const std::string & param_name, std::string & value);
538
546 [[deprecated]] void set_prefixes(const std::string & topic_prefix);
547
548 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
549
550 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
551 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
552 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
553 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;
554
555 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
556 control_msgs::msg::PidState pid_state_msg_;
557 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;
558
559 Pid pid_;
560};
561
562} // namespace control_toolbox
563
564#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:546
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:450
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:766
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr getParametersCallbackHandle()
Return PID parameters callback handle.
Definition pid_ros.hpp:495
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:100
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid_ros.cpp:775
void set_current_cmd(double cmd)
Set current command for this PID controller.
Definition pid_ros.cpp:533
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:744
double getCurrentCmd()
Return current command for this PID controller.
Definition pid_ros.cpp:768
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
Definition pid_ros.cpp:537
double get_current_cmd()
Return current command for this PID controller.
Definition pid_ros.cpp:535
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > getPidStatePublisher()
Return PID state publisher.
Definition pid_ros.cpp:770
bool initPid()
Initialize the PID controller based on already set parameters.
Definition pid_ros.cpp:742
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:434
void printValues()
Print to console the current parameters.
Definition pid_ros.cpp:780
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:759
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:122
Pid::Gains getGains()
Get PID gains for the controller.
Definition pid_ros.cpp:758
Pid::Gains get_gains()
Get PID gains for the controller.
Definition pid_ros.cpp:448
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr get_parameters_callback_handle()
Return PID parameters callback handle.
Definition pid_ros.hpp:484
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > get_pid_state_publisher()
Return PID state publisher.
Definition pid_ros.cpp:429
void reset()
Reset the state of this PID controller.
Definition pid_ros.cpp:420
Generic Proportional–Integral–Derivative (PID) controller.
Definition pid.hpp:282
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:288