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>::infinity()),
86 i_max(std::numeric_limits<double>::infinity()),
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(
141 fmt::format(
"PID requires i_min to be smaller or equal to 0 (i_min: {})",
i_min));
145 throw std::invalid_argument(
146 fmt::format(
"PID requires i_max to be greater or equal to 0 (i_max: {})",
i_max));
149 type != NONE && type != UNDEFINED && type != LEGACY && type != BACK_CALCULATION &&
150 type != CONDITIONAL_INTEGRATION)
152 throw std::invalid_argument(
"AntiWindupStrategy has an invalid type");
156 void print()
const { std::cout << string() << std::endl; }
158 std::string string()
const
161 "antiwindup_strat: {}\ti_max: {}\ti_min: {}\ttracking_time_constant: {}\terror_deadband: {}",
165 operator std::string()
const {
return to_string(); }
167 constexpr bool operator==(Value
other)
const {
return type ==
other; }
168 constexpr bool operator!=(Value
other)
const {
return type !=
other; }
170 std::string to_string()
const
174 case BACK_CALCULATION:
175 return "back_calculation";
176 case CONDITIONAL_INTEGRATION:
177 return "conditional_integration";
188 Value type = UNDEFINED;
189 double i_min = -std::numeric_limits<double>::infinity();
190 double i_max = std::numeric_limits<double>::infinity();
199 std::numeric_limits<double>::epsilon();
203inline bool is_zero(T value, T
tolerance = std::numeric_limits<T>::epsilon())
303 [[deprecated(
"Use constructor with AntiWindupStrategy instead.")]]
304 Gains(
double p,
double i,
double d,
double i_max,
double i_min)
334 [[deprecated(
"Use constructor with AntiWindupStrategy instead.")]]
365 double p,
double i,
double d,
double u_max,
double u_min,
379 bool validate(std::string &
error_msg)
const
388 error_msg =
"Gains: u_min and u_max must not be NaN";
395 catch (
const std::exception & e)
397 error_msg = e.what();
405 "Use constructor with AntiWindupStrategy only. The default constructor might be deleted in "
410 void print()
const { std::cout << string() << std::endl; }
412 std::string string()
const
415 "Gains(p: {}, i: {}, d: {}, u_max: {}, u_min: {}, antiwindup_strat: '{}')",
p_gain_,
423 std::numeric_limits<double>::infinity();
425 -std::numeric_limits<double>::infinity();
426 double u_max_ = std::numeric_limits<double>::infinity();
427 double u_min_ = -std::numeric_limits<double>::infinity();
448 [[deprecated(
"Use constructor with AntiWindupStrategy only.")]]
450 double p = 0.0,
double i = 0.0,
double d = 0.0,
451 double i_max = std::numeric_limits<double>::infinity(),
452 double i_min = -std::numeric_limits<double>::infinity(),
bool antiwindup =
false);
469 double p,
double i,
double d,
double u_max,
double u_min,
498 [[deprecated(
"Use initialize with AntiWindupStrategy instead.")]]
500 double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
517 [[deprecated(
"Use initialize() instead")]]
void initPid(
518 double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
536 double p,
double i,
double d,
double u_max,
double u_min,
567 void get_gains(
double &
p,
double & i,
double &
d,
double & i_max,
double & i_min);
577 [[deprecated(
"Use get_gains() instead")]]
void getGains(
578 double &
p,
double & i,
double &
d,
double & i_max,
double & i_min);
594 [[deprecated(
"Use get_gains overload with AntiWindupStrategy argument.")]]
596 double &
p,
double & i,
double &
d,
double & i_max,
double & i_min,
bool &
antiwindup);
610 [[deprecated(
"Use get_gains() instead")]]
void getGains(
611 double &
p,
double & i,
double &
d,
double & i_max,
double & i_min,
bool &
antiwindup);
627 double &
p,
double & i,
double &
d,
double &
u_max,
double &
u_min,
670 [[deprecated(
"Use set_gains with AntiWindupStrategy instead.")]]
687 [[deprecated(
"Use set_gains() instead")]]
void setGains(
688 double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
707 double p,
double i,
double d,
double u_max,
double u_min,
726 [[deprecated(
"Use set_gains() instead")]]
void setGains(
const Gains &
gains);
855 double error,
double error_dot,
const std::chrono::nanoseconds &
dt_ns);
865 [[deprecated(
"Use set_current_cmd() instead")]]
void setCurrentCmd(
double cmd);
875 [[deprecated(
"Use get_current_cmd() instead")]]
double getCurrentCmd();
897 double &
pe,
double &
ie,
double &
de);
911 gains_box_ =
source.gains_box_;
925 std::numeric_limits<double>::infinity(),
926 -std::numeric_limits<double>::infinity(),
932 double p_error_last_ = 0;