33#ifndef CONTROL_TOOLBOX__PID_HPP_
34#define CONTROL_TOOLBOX__PID_HPP_
42#include "fmt/format.h"
43#include "rclcpp/duration.hpp"
44#include "realtime_tools/realtime_thread_safe_box.hpp"
80 CONDITIONAL_INTEGRATION
85 i_min(std::numeric_limits<double>::quiet_NaN()),
86 i_max(std::numeric_limits<double>::quiet_NaN()),
93 void set_type(
const std::string &
s)
95 if (
s ==
"back_calculation")
97 type = BACK_CALCULATION;
99 else if (
s ==
"conditional_integration")
101 type = CONDITIONAL_INTEGRATION;
103 else if (
s ==
"legacy")
106 std::cout <<
"Using the legacy anti-windup technique is deprecated. This option will be "
107 "removed by the ROS 2 Kilted Kaiju release."
110 else if (
s ==
"none")
117 throw std::invalid_argument(
118 "AntiWindupStrategy: Unknown antiwindup strategy : '" +
s +
119 "'. Valid strategies are: 'back_calculation', 'conditional_integration', 'legacy', "
124 void validate()
const
126 if (type == UNDEFINED)
128 throw std::invalid_argument(
"AntiWindupStrategy is UNDEFINED. Please set a valid type");
131 type == BACK_CALCULATION &&
134 throw std::invalid_argument(
135 "AntiWindupStrategy 'back_calculation' requires a valid positive tracking time constant "
136 "(tracking_time_constant)");
140 throw std::invalid_argument(
142 "AntiWindupStrategy 'legacy' requires i_min < i_max and to be finite (i_min: {}, i_max: "
146 if (type != LEGACY && (std::isfinite(
i_min) || std::isfinite(
i_max)))
148 std::cout <<
"Warning: The i_min and i_max are only valid for the deprecated LEGACY "
149 "antiwindup strategy. Please use the AntiWindupStrategy::set_type() method to "
150 "set the type of antiwindup strategy you want to use."
154 type != NONE && type != UNDEFINED && type != LEGACY && type != BACK_CALCULATION &&
155 type != CONDITIONAL_INTEGRATION)
157 throw std::invalid_argument(
"AntiWindupStrategy has an invalid type");
161 operator std::string()
const {
return to_string(); }
163 constexpr bool operator==(Value
other)
const {
return type ==
other; }
164 constexpr bool operator!=(Value
other)
const {
return type !=
other; }
166 std::string to_string()
const
170 case BACK_CALCULATION:
171 return "back_calculation";
172 case CONDITIONAL_INTEGRATION:
173 return "conditional_integration";
184 Value type = UNDEFINED;
185 double i_min = std::numeric_limits<double>::quiet_NaN();
186 double i_max = std::numeric_limits<double>::quiet_NaN();
195 std::numeric_limits<double>::epsilon();
199inline bool is_zero(T value, T
tolerance = std::numeric_limits<T>::epsilon())
299 [[deprecated(
"Use constructor with AntiWindupStrategy instead.")]]
300 Gains(
double p,
double i,
double d,
double i_max,
double i_min)
330 [[deprecated(
"Use constructor with AntiWindupStrategy instead.")]]
361 double p,
double i,
double d,
double u_max,
double u_min,
375 throw std::invalid_argument(
"Gains: u_min and u_max must not be NaN");
379 std::cout <<
"Received invalid u_min and u_max values: " <<
"u_min: " <<
u_min
380 <<
", u_max: " <<
u_max <<
". Setting saturation to false." << std::endl;
381 u_max_ = std::numeric_limits<double>::infinity();
382 u_min_ = -std::numeric_limits<double>::infinity();
386 bool validate(std::string &
error_msg)
const
400 error_msg =
"Gains: u_min and u_max must not be NaN";
407 catch (
const std::exception & e)
409 error_msg = e.what();
417 "Use constructor with AntiWindupStrategy only. The default constructor might be deleted in "
435 double u_max_ = std::numeric_limits<double>::infinity();
436 double u_min_ = -std::numeric_limits<double>::infinity();
457 [[deprecated(
"Use constructor with AntiWindupStrategy only.")]]
459 double p = 0.0,
double i = 0.0,
double d = 0.0,
double i_max = 0.0,
double i_min = -0.0,
477 double p,
double i,
double d,
double u_max,
double u_min,
506 [[deprecated(
"Use initialize with AntiWindupStrategy instead.")]]
508 double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
525 [[deprecated(
"Use initialize() instead")]]
void initPid(
526 double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
544 double p,
double i,
double d,
double u_max,
double u_min,
575 void get_gains(
double &
p,
double & i,
double &
d,
double & i_max,
double & i_min);
585 [[deprecated(
"Use get_gains() instead")]]
void getGains(
586 double &
p,
double & i,
double &
d,
double & i_max,
double & i_min);
602 [[deprecated(
"Use get_gains overload with AntiWindupStrategy argument.")]]
604 double &
p,
double & i,
double &
d,
double & i_max,
double & i_min,
bool &
antiwindup);
618 [[deprecated(
"Use get_gains() instead")]]
void getGains(
619 double &
p,
double & i,
double &
d,
double & i_max,
double & i_min,
bool &
antiwindup);
635 double &
p,
double & i,
double &
d,
double &
u_max,
double &
u_min,
678 [[deprecated(
"Use set_gains with AntiWindupStrategy instead.")]]
695 [[deprecated(
"Use set_gains() instead")]]
void setGains(
696 double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
715 double p,
double i,
double d,
double u_max,
double u_min,
734 [[deprecated(
"Use set_gains() instead")]]
void setGains(
const Gains &
gains);
863 double error,
double error_dot,
const std::chrono::nanoseconds &
dt_ns);
873 [[deprecated(
"Use set_current_cmd() instead")]]
void setCurrentCmd(
double cmd);
883 [[deprecated(
"Use get_current_cmd() instead")]]
double getCurrentCmd();
905 double &
pe,
double &
ie,
double &
de);
919 gains_box_ =
source.gains_box_;
933 std::numeric_limits<double>::infinity(),
934 -std::numeric_limits<double>::infinity(),
940 double p_error_last_ = 0;