diff --git a/control_toolbox/include/control_toolbox/pid.hpp b/control_toolbox/include/control_toolbox/pid.hpp index f0d9ea25..f343bbcf 100644 --- a/control_toolbox/include/control_toolbox/pid.hpp +++ b/control_toolbox/include/control_toolbox/pid.hpp @@ -57,14 +57,9 @@ namespace control_toolbox * \param u_min Lower output clamp. * \param tracking_time_constant Specifies the tracking time constant for the 'back_calculation' strategy. If set * to 0.0 when this strategy is selected, a recommended default value will be applied. - * \param legacy_antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * \param error_deadband Error deadband is used to stop integration when the error is within the given range. - * \param type Specifies the antiwindup strategy type. Valid values are: + * \param error_deadband Error deadband is used to stop integration when the error is within the given range. + * \param type Specifies the antiwindup strategy type. Valid values are: * - `NONE`: No antiwindup strategy applied. - * - `LEGACY`: Legacy antiwindup strategy, which limits the integral term to prevent windup (deprecated: This option will be removed in a future release). * - `BACK_CALCULATION`: Back calculation antiwindup strategy, which uses a tracking time constant. * - `CONDITIONAL_INTEGRATION`: Conditional integration antiwindup strategy, which integrates only when certain conditions are met. */ @@ -75,16 +70,14 @@ struct AntiWindupStrategy { UNDEFINED = -1, NONE, - LEGACY, BACK_CALCULATION, CONDITIONAL_INTEGRATION }; AntiWindupStrategy() - : type(UNDEFINED), - i_min(std::numeric_limits::quiet_NaN()), - i_max(std::numeric_limits::quiet_NaN()), - legacy_antiwindup(false), + : type(NONE), + i_max(std::numeric_limits::infinity()), + i_min(-std::numeric_limits::infinity()), tracking_time_constant(0.0), error_deadband(std::numeric_limits::epsilon()) { @@ -100,13 +93,6 @@ struct AntiWindupStrategy { type = CONDITIONAL_INTEGRATION; } - else if (s == "legacy") - { - type = LEGACY; - std::cout << "Using the legacy anti-windup technique is deprecated. This option will be " - "removed by the ROS 2 Kilted Kaiju release." - << std::endl; - } else if (s == "none") { type = NONE; @@ -116,7 +102,7 @@ struct AntiWindupStrategy type = UNDEFINED; throw std::invalid_argument( "AntiWindupStrategy: Unknown antiwindup strategy : '" + s + - "'. Valid strategies are: 'back_calculation', 'conditional_integration', 'legacy', " + "'. Valid strategies are: 'back_calculation', 'conditional_integration', " "'none'."); } } @@ -135,23 +121,15 @@ struct AntiWindupStrategy "AntiWindupStrategy 'back_calculation' requires a valid positive tracking time constant " "(tracking_time_constant)"); } - if (type == LEGACY && ((i_min > i_max) || !std::isfinite(i_min) || !std::isfinite(i_max))) + if (type != NONE && ((i_min > i_max) || !std::isfinite(i_min) || !std::isfinite(i_max))) { throw std::invalid_argument( fmt::format( - "AntiWindupStrategy 'legacy' requires i_min < i_max and to be finite (i_min: {}, i_max: " - "{})", + "AntiWindupStrategy requires i_min < i_max and to be finite (i_min: {}, i_max: {})", i_min, i_max)); } - if (type != LEGACY && (std::isfinite(i_min) || std::isfinite(i_max))) - { - std::cout << "Warning: The i_min and i_max are only valid for the deprecated LEGACY " - "antiwindup strategy. Please use the AntiWindupStrategy::set_type() method to " - "set the type of antiwindup strategy you want to use." - << std::endl; - } if ( - type != NONE && type != UNDEFINED && type != LEGACY && type != BACK_CALCULATION && + type != NONE && type != UNDEFINED && type != BACK_CALCULATION && type != CONDITIONAL_INTEGRATION) { throw std::invalid_argument("AntiWindupStrategy has an invalid type"); @@ -171,8 +149,6 @@ struct AntiWindupStrategy return "back_calculation"; case CONDITIONAL_INTEGRATION: return "conditional_integration"; - case LEGACY: - return "legacy"; case NONE: return "none"; case UNDEFINED: @@ -182,10 +158,8 @@ struct AntiWindupStrategy } Value type = UNDEFINED; - double i_min = std::numeric_limits::quiet_NaN(); /**< Minimum allowable integral term. */ - double i_max = std::numeric_limits::quiet_NaN(); /**< Maximum allowable integral term. */ - - bool legacy_antiwindup = false; /**< Use legacy anti-windup strategy. */ + double i_max = std::numeric_limits::infinity(); /**< Maximum allowable integral term. */ + double i_min = -std::numeric_limits::infinity(); /**< Minimum allowable integral term. */ // tracking_time_constant Specifies the tracking time constant for the 'back_calculation' // strategy. If set to 0.0 a recommended default value will be applied. @@ -265,8 +239,8 @@ inline bool is_zero(T value, T tolerance = std::numeric_limits::epsilon()) Initialize and compute at each control step: \code{.cpp} control_toolbox::Pid pid; - pid.initialize(6.0, 1.0, 2.0, -5.0, 5.0, - 2.0, control_toolbox::AntiwindupStrategy::BACK_CALCULATION); + pid.initialize(6.0, 1.0, 2.0, 5.0, -5.0, + control_toolbox::AntiWindupStrategy::BACK_CALCULATION); rclcpp::Time last = get_clock()->now(); while (running) { rclcpp::Time now = get_clock()->now(); @@ -286,64 +260,6 @@ class Pid */ struct Gains { - /*! - * \brief Optional constructor for passing in values without antiwindup and saturation - * - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * - */ - [[deprecated("Use constructor with AntiWindupStrategy instead.")]] - Gains(double p, double i, double d, double i_max, double i_min) - : p_gain_(p), - i_gain_(i), - d_gain_(d), - i_max_(i_max), - i_min_(i_min), - u_max_(std::numeric_limits::infinity()), - u_min_(-std::numeric_limits::infinity()), - antiwindup_(false) - { - antiwindup_strat_.type = AntiWindupStrategy::LEGACY; - antiwindup_strat_.i_max = i_max; - antiwindup_strat_.i_min = i_min; - antiwindup_strat_.legacy_antiwindup = true; - } - - /*! - * \brief Optional constructor for passing in values without saturation - * - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * \param antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * - */ - [[deprecated("Use constructor with AntiWindupStrategy instead.")]] - Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup) - : p_gain_(p), - i_gain_(i), - d_gain_(d), - i_max_(i_max), - i_min_(i_min), - u_max_(std::numeric_limits::infinity()), - u_min_(-std::numeric_limits::infinity()), - antiwindup_(antiwindup) - { - antiwindup_strat_.type = AntiWindupStrategy::LEGACY; - antiwindup_strat_.i_max = i_max; - antiwindup_strat_.i_min = i_min; - antiwindup_strat_.legacy_antiwindup = antiwindup; - } - /*! * \brief Constructor for passing in values. * @@ -367,7 +283,6 @@ class Pid i_min_(antiwindup_strat.i_min), u_max_(u_max), u_min_(u_min), - antiwindup_(antiwindup_strat.legacy_antiwindup), antiwindup_strat_(antiwindup_strat) { if (std::isnan(u_min) || std::isnan(u_max)) @@ -412,53 +327,26 @@ class Pid return true; } - // Default constructor - [[deprecated( - "Use constructor with AntiWindupStrategy only. The default constructor might be deleted in " - "future")]] Gains() - { - } - void print() const { std::cout << "Gains: p: " << p_gain_ << ", i: " << i_gain_ << ", d: " << d_gain_ << ", i_max: " << i_max_ << ", i_min: " << i_min_ << ", u_max: " << u_max_ - << ", u_min: " << u_min_ << ", antiwindup: " << antiwindup_ - << ", antiwindup_strat: " << antiwindup_strat_.to_string() << std::endl; + << ", u_min: " << u_min_ << ", antiwindup_strat: " << antiwindup_strat_.to_string() + << std::endl; } double p_gain_ = 0.0; /**< Proportional gain. */ double i_gain_ = 0.0; /**< Integral gain. */ double d_gain_ = 0.0; /**< Derivative gain. */ - double i_max_ = 0.0; /**< Maximum allowable integral term. */ - double i_min_ = 0.0; /**< Minimum allowable integral term. */ + double i_max_ = + std::numeric_limits::infinity(); /**< Maximum allowable integral term. */ + double i_min_ = + -std::numeric_limits::infinity(); /**< Minimum allowable integral term. */ double u_max_ = std::numeric_limits::infinity(); /**< Maximum allowable output. */ double u_min_ = -std::numeric_limits::infinity(); /**< Minimum allowable output. */ - bool antiwindup_ = false; /**< Anti-windup. */ AntiWindupStrategy antiwindup_strat_; /**< Anti-windup strategy. */ }; - /*! - * \brief Constructor, zeros out Pid values when created and - * initialize Pid-gains and integral term limits. - * - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * \param antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * - * \throws An std::invalid_argument exception is thrown if i_min > i_max - */ - [[deprecated("Use constructor with AntiWindupStrategy only.")]] - Pid( - double p = 0.0, double i = 0.0, double d = 0.0, double i_max = 0.0, double i_min = -0.0, - bool antiwindup = false); - /*! * \brief Constructor, initialize Pid-gains and term limits. * @@ -471,11 +359,13 @@ class Pid 'conditional_integration', or 'none'. Note that the 'back_calculation' strategy use the tracking_time_constant parameter to tune the anti-windup behavior. * - * \throws An std::invalid_argument exception is thrown if u_min > u_max + * \throws An std::invalid_argument exception is thrown if u_min > u_max. */ Pid( - double p, double i, double d, double u_max, double u_min, - const AntiWindupStrategy & antiwindup_strat); + double p = 0.0, double i = 0.0, double d = 0.0, + double u_max = std::numeric_limits::infinity(), + double u_min = -std::numeric_limits::infinity(), + const AntiWindupStrategy & antiwindup_strat = AntiWindupStrategy()); /*! * \brief Copy constructor required for preventing mutexes from being copied @@ -488,25 +378,6 @@ class Pid */ ~Pid(); - /*! - * \brief Zeros out Pid values and initialize Pid-gains and term limits - * - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * \param antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * \return True if all parameters are successfully set, False otherwise. - * \note New gains are not applied if i_min_ > i_max_ - */ - [[deprecated("Use initialize with AntiWindupStrategy instead.")]] - bool initialize( - double p, double i, double d, double i_max, double i_min, bool antiwindup = false); - /*! * \brief Initialize Pid-gains and term limits. * @@ -520,7 +391,7 @@ class Pid tracking_time_constant parameter to tune the anti-windup behavior. * \return True if all parameters are successfully set, False otherwise. * - * \note New gains are not applied if i_min_ > i_max_ or u_min > u_max + * \note New gains are not applied if u_min > u_max. */ bool initialize( double p, double i, double d, double u_max, double u_min, @@ -544,36 +415,6 @@ class Pid */ void clear_saved_iterm(); - /*! - * \brief Get PID gains for the controller. - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * - * \note This method is not RT safe - */ - void get_gains(double & p, double & i, double & d, double & i_max, double & i_min); - - /*! - * \brief Get PID gains for the controller. - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * \param antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * - * \note This method is not RT safe - */ - [[deprecated("Use get_gains overload with AntiWindupStrategy argument.")]] - void get_gains( - double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup); - /*! * \brief Get PID gains for the controller (preferred). * \param p The proportional gain. @@ -607,25 +448,6 @@ class Pid */ Gains get_gains_rt() { return gains_; } - /*! - * \brief Set PID gains for the controller. - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * \param antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * \return True if all parameters are successfully set, False otherwise. - * - * \note New gains are not applied if i_min > i_max - * \note This method is not RT safe - */ - [[deprecated("Use set_gains with AntiWindupStrategy instead.")]] - bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false); - /*! * \brief Set PID gains for the controller. * @@ -639,7 +461,7 @@ class Pid tracking_time_constant parameter to tune the anti-windup behavior. * \return True if all parameters are successfully set, False otherwise. * - * \note New gains are not applied if i_min_ > i_max_ or u_min > u_max + * \note New gains are not applied if u_min > u_max * \note This method is not RT safe */ bool set_gains( diff --git a/control_toolbox/include/control_toolbox/pid_ros.hpp b/control_toolbox/include/control_toolbox/pid_ros.hpp index b12a2777..8286d27a 100644 --- a/control_toolbox/include/control_toolbox/pid_ros.hpp +++ b/control_toolbox/include/control_toolbox/pid_ros.hpp @@ -155,45 +155,6 @@ class PidROS const std::string & param_prefix, const std::string & topic_prefix, bool activate_state_publisher); - /*! - * \brief Initialize the PID controller and set the parameters - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * \param antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * \return True if all parameters are successfully set, False otherwise. - * - * \note New gains are not applied if i_min_ > i_max_ - */ - [[deprecated("Use initialize_from_args with AntiWindupStrategy instead.")]] - bool initialize_from_args( - double p, double i, double d, double i_max, double i_min, bool antiwindup); - - /*! - * \brief Initialize the PID controller and set the parameters - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max The max integral windup. - * \param i_min The min integral windup. - * \param antiwindup Anti-windup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * \param save_i_term save integrator output between resets. - * \return True if all parameters are successfully set, False otherwise. - * - * \note New gains are not applied if i_min_ > i_max_ - */ - [[deprecated("Use initialize_from_args with AntiWindupStrategy instead.")]] - bool initialize_from_args( - double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term); - /*! * \brief Initialize the PID controller and set the parameters. * @@ -270,25 +231,6 @@ class PidROS /*! * \brief Set PID gains for the controller. - * \param p The proportional gain. - * \param i The integral gain. - * \param d The derivative gain. - * \param i_max Upper integral clamp. - * \param i_min Lower integral clamp. - * \param antiwindup Antiwindup functionality. When set to true, limits - the integral error to prevent windup; otherwise, constrains the - integral contribution to the control output. i_max and - i_min are applied in both scenarios. - * \return True if all parameters are successfully set, False otherwise. - * - * \note New gains are not applied if i_min > i_max - * \note This method is not RT safe - */ - [[deprecated("Use set_gains with AntiWindupStrategy instead.")]] - bool set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false); - - /*! - * \brief Set PID gains for the controller (preferred). * * \param p The proportional gain. * \param i The integral gain. @@ -300,7 +242,7 @@ class PidROS tracking_time_constant parameter to tune the anti-windup behavior. * \return True if all parameters are successfully set, False otherwise. * - * \note New gains are not applied if u_min_ > u_max_. + * \note New gains are not applied if u_min > u_max. * \note This method is not RT safe */ bool set_gains( diff --git a/control_toolbox/src/pid.cpp b/control_toolbox/src/pid.cpp index 8b653ebe..f8a03272 100644 --- a/control_toolbox/src/pid.cpp +++ b/control_toolbox/src/pid.cpp @@ -45,29 +45,6 @@ namespace control_toolbox { -constexpr double UMAX_INFINITY = std::numeric_limits::infinity(); - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -Pid::Pid(double p, double i, double d, double i_max, double i_min, bool antiwindup) -{ - if (i_min > i_max) - { - throw std::invalid_argument("received i_min > i_max"); - } - AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; - antiwindup_strat.i_max = i_max; - antiwindup_strat.i_min = i_min; - antiwindup_strat.legacy_antiwindup = antiwindup; - set_gains(p, i, d, UMAX_INFINITY, -UMAX_INFINITY, antiwindup_strat); - - // Initialize saved i-term values - clear_saved_iterm(); - - reset(); -} -#pragma GCC diagnostic pop Pid::Pid( double p, double i, double d, double u_max, double u_min, @@ -99,19 +76,6 @@ Pid::Pid(const Pid & source) Pid::~Pid() {} -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -bool Pid::initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup) -{ - if (set_gains(p, i, d, i_max, i_min, antiwindup)) - { - reset(); - return true; - } - return false; -} -#pragma GCC diagnostic pop - bool Pid::initialize( double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy & antiwindup_strat) @@ -145,28 +109,6 @@ void Pid::reset(bool save_i_term) void Pid::clear_saved_iterm() { i_term_ = 0.0; } -void Pid::get_gains(double & p, double & i, double & d, double & i_max, double & i_min) -{ - double u_max; - double u_min; - AntiWindupStrategy antiwindup_strat; - get_gains(p, i, d, u_max, u_min, antiwindup_strat); - i_max = antiwindup_strat.i_max; - i_min = antiwindup_strat.i_min; -} - -void Pid::get_gains( - double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup) -{ - double u_max; - double u_min; - AntiWindupStrategy antiwindup_strat; - get_gains(p, i, d, u_max, u_min, antiwindup_strat); - i_max = antiwindup_strat.i_max; - i_min = antiwindup_strat.i_min; - antiwindup = antiwindup_strat.legacy_antiwindup; -} - void Pid::get_gains( double & p, double & i, double & d, double & u_max, double & u_min, AntiWindupStrategy & antiwindup_strat) @@ -186,26 +128,6 @@ Pid::Gains Pid::get_gains() return gains_box_.get(); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -bool Pid::set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup) -{ - try - { - Gains gains(p, i, d, i_max, i_min, antiwindup); - if (set_gains(gains)) - { - return true; - } - } - catch (const std::exception & e) - { - std::cerr << e.what() << '\n'; - } - return false; -} -#pragma GCC diagnostic pop - bool Pid::set_gains( double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy & antiwindup_strat) @@ -354,35 +276,11 @@ double Pid::compute_command(double error, double error_dot, const double & dt_s) "PID: Antiwindup strategy cannot be UNDEFINED. Please set a valid antiwindup strategy."); } - // Calculate integral contribution to command const bool is_error_in_deadband_zone = control_toolbox::is_zero(error, gains_.antiwindup_strat_.error_deadband); - if (!is_error_in_deadband_zone && gains_.antiwindup_strat_.type == AntiWindupStrategy::LEGACY) - { - if (gains_.antiwindup_strat_.legacy_antiwindup) - { - // Prevent i_term_ from climbing higher than permitted by i_max_/i_min_ - i_term_ = - std::clamp(i_term_ + gains_.i_gain_ * dt_s * p_error_, gains_.i_min_, gains_.i_max_); - } - else - { - i_term_ += gains_.i_gain_ * dt_s * p_error_; - } - } // Compute the command - if ( - !gains_.antiwindup_strat_.legacy_antiwindup && - gains_.antiwindup_strat_.type == AntiWindupStrategy::LEGACY) - { - // Limit i_term so that the limit is meaningful in the output - cmd_unsat_ = p_term + std::clamp(i_term_, gains_.i_min_, gains_.i_max_) + d_term; - } - else - { - cmd_unsat_ = p_term + i_term_ + d_term; - } + cmd_unsat_ = p_term + i_term_ + d_term; if (std::isfinite(gains_.u_min_) || std::isfinite(gains_.u_max_)) { @@ -400,7 +298,6 @@ double Pid::compute_command(double error, double error_dot, const double & dt_s) { cmd_ = cmd_unsat_; } - if (!is_error_in_deadband_zone) { if ( @@ -409,12 +306,16 @@ double Pid::compute_command(double error, double error_dot, const double & dt_s) { i_term_ += dt_s * (gains_.i_gain_ * error + 1 / gains_.antiwindup_strat_.tracking_time_constant * (cmd_ - cmd_unsat_)); + + i_term_ = std::clamp(i_term_, gains_.i_min_, gains_.i_max_); } else if (gains_.antiwindup_strat_.type == AntiWindupStrategy::CONDITIONAL_INTEGRATION) { if (!(!is_zero(cmd_unsat_ - cmd_) && error * cmd_unsat_ > 0)) { i_term_ += dt_s * gains_.i_gain_ * error; + + i_term_ = std::clamp(i_term_, gains_.i_min_, gains_.i_max_); } } else if (gains_.antiwindup_strat_.type == AntiWindupStrategy::NONE) diff --git a/control_toolbox/src/pid_ros.cpp b/control_toolbox/src/pid_ros.cpp index 2654b580..ddf445fa 100644 --- a/control_toolbox/src/pid_ros.cpp +++ b/control_toolbox/src/pid_ros.cpp @@ -40,7 +40,7 @@ namespace control_toolbox { -constexpr double UMAX_INFINITY = std::numeric_limits::infinity(); +constexpr double MAX_INFINITY = std::numeric_limits::infinity(); #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wdeprecated-declarations" PidROS::PidROS( @@ -255,12 +255,13 @@ bool PidROS::get_string_param(const std::string & param_name, std::string & valu bool PidROS::initialize_from_ros_parameters() { double p, i, d, i_max, i_min, u_max, u_min, tracking_time_constant, error_deadband; - p = i = d = i_max = i_min = tracking_time_constant = std::numeric_limits::quiet_NaN(); + p = i = d = tracking_time_constant = std::numeric_limits::quiet_NaN(); error_deadband = std::numeric_limits::epsilon(); - u_max = UMAX_INFINITY; - u_min = -UMAX_INFINITY; - bool antiwindup = false; - std::string antiwindup_strat_str = "legacy"; + i_max = MAX_INFINITY; + i_min = -MAX_INFINITY; + u_max = MAX_INFINITY; + u_min = -MAX_INFINITY; + std::string antiwindup_strat_str = "none"; bool all_params_available = true; all_params_available &= get_double_param(param_prefix_ + "p", p); @@ -278,10 +279,9 @@ bool PidROS::initialize_from_ros_parameters() get_boolean_param(param_prefix_ + "saturation", saturation); if (!saturation) { - u_max = UMAX_INFINITY; - u_min = -UMAX_INFINITY; + u_max = MAX_INFINITY; + u_min = -MAX_INFINITY; } - get_boolean_param(param_prefix_ + "antiwindup", antiwindup); get_string_param(param_prefix_ + "antiwindup_strategy", antiwindup_strat_str); declare_param(param_prefix_ + "save_i_term", rclcpp::ParameterValue(false)); declare_param( @@ -292,17 +292,11 @@ bool PidROS::initialize_from_ros_parameters() set_parameter_event_callback(); } - RCLCPP_WARN_EXPRESSION( - node_logging_->get_logger(), antiwindup_strat_str == "legacy", - "Using the legacy anti-windup technique is deprecated. This option will be removed by the ROS " - "2 Kilted Kaiju release."); - AntiWindupStrategy antiwindup_strat; antiwindup_strat.set_type(antiwindup_strat_str); antiwindup_strat.i_max = i_max; antiwindup_strat.i_min = i_min; antiwindup_strat.tracking_time_constant = tracking_time_constant; - antiwindup_strat.legacy_antiwindup = antiwindup; antiwindup_strat.error_deadband = error_deadband; try @@ -331,34 +325,6 @@ void PidROS::declare_param(const std::string & param_name, rclcpp::ParameterValu } } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -bool PidROS::initialize_from_args( - double p, double i, double d, double i_max, double i_min, bool antiwindup) -{ - AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; - antiwindup_strat.i_max = i_max; - antiwindup_strat.i_min = i_min; - antiwindup_strat.legacy_antiwindup = antiwindup; - - return initialize_from_args(p, i, d, UMAX_INFINITY, -UMAX_INFINITY, antiwindup_strat, false); -} -#pragma GCC diagnostic pop - -bool PidROS::initialize_from_args( - double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term) -{ - AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; - antiwindup_strat.i_max = i_max; - antiwindup_strat.i_min = i_min; - antiwindup_strat.legacy_antiwindup = antiwindup; - - return initialize_from_args( - p, i, d, UMAX_INFINITY, -UMAX_INFINITY, antiwindup_strat, save_i_term); -} - bool PidROS::initialize_from_args( double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy & antiwindup_strat, bool save_i_term) @@ -386,9 +352,6 @@ bool PidROS::initialize_from_args( param_prefix_ + "i_clamp_min", rclcpp::ParameterValue(gains.antiwindup_strat_.i_min)); declare_param(param_prefix_ + "u_clamp_max", rclcpp::ParameterValue(gains.u_max_)); declare_param(param_prefix_ + "u_clamp_min", rclcpp::ParameterValue(gains.u_min_)); - declare_param( - param_prefix_ + "antiwindup", - rclcpp::ParameterValue(gains.antiwindup_strat_.legacy_antiwindup)); declare_param( param_prefix_ + "tracking_time_constant", rclcpp::ParameterValue(antiwindup_strat.tracking_time_constant)); @@ -447,16 +410,6 @@ double PidROS::compute_command(double error, double error_dot, const rclcpp::Dur Pid::Gains PidROS::get_gains() { return pid_.get_gains(); } -bool PidROS::set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup) -{ - AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; - antiwindup_strat.i_max = i_max; - antiwindup_strat.i_min = i_min; - antiwindup_strat.legacy_antiwindup = antiwindup; - return set_gains(p, i, d, UMAX_INFINITY, -UMAX_INFINITY, antiwindup_strat); -} - bool PidROS::set_gains( double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy & antiwindup_strat) @@ -491,7 +444,6 @@ bool PidROS::set_gains(const Pid::Gains & gains) rclcpp::Parameter( param_prefix_ + "tracking_time_constant", gains.antiwindup_strat_.tracking_time_constant), - rclcpp::Parameter(param_prefix_ + "antiwindup", gains.antiwindup_strat_.legacy_antiwindup), rclcpp::Parameter( param_prefix_ + "error_deadband", gains.antiwindup_strat_.error_deadband), rclcpp::Parameter(param_prefix_ + "saturation", true), @@ -557,7 +509,6 @@ void PidROS::print_values() << " U_Max: " << gains.u_max_ << "\n" << " U_Min: " << gains.u_min_ << "\n" << " Tracking_Time_Constant: " << gains.antiwindup_strat_.tracking_time_constant << "\n" - << " Antiwindup: " << gains.antiwindup_strat_.legacy_antiwindup << "\n" << " Antiwindup_Strategy: " << gains.antiwindup_strat_.to_string() << "\n" << "\n" << " P Error: " << p_error << "\n" @@ -606,8 +557,8 @@ void PidROS::set_parameter_event_callback() RCLCPP_WARN( node_logging_->get_logger(), "Saturation is set to false, Changing the u_min and u_max to -inf and inf"); - gains.u_min_ = -UMAX_INFINITY; - gains.u_max_ = UMAX_INFINITY; + gains.u_max_ = MAX_INFINITY; + gains.u_min_ = -MAX_INFINITY; } else { @@ -655,7 +606,7 @@ void PidROS::set_parameter_event_callback() } else if (param_name == param_prefix_ + "u_clamp_max") { - gains.u_max_ = saturation ? parameter.get_value() : UMAX_INFINITY; + gains.u_max_ = saturation ? parameter.get_value() : MAX_INFINITY; RCLCPP_WARN_EXPRESSION( node_logging_->get_logger(), !saturation, "Saturation is set to false, Changing the u_clamp_max inf"); @@ -663,7 +614,7 @@ void PidROS::set_parameter_event_callback() } else if (param_name == param_prefix_ + "u_clamp_min") { - gains.u_min_ = saturation ? parameter.get_value() : -UMAX_INFINITY; + gains.u_min_ = saturation ? parameter.get_value() : -MAX_INFINITY; RCLCPP_WARN_EXPRESSION( node_logging_->get_logger(), !saturation, "Saturation is set to false, Changing the u_clamp_min -inf"); @@ -674,11 +625,6 @@ void PidROS::set_parameter_event_callback() gains.antiwindup_strat_.tracking_time_constant = parameter.get_value(); changed = true; } - else if (param_name == param_prefix_ + "antiwindup") - { - gains.antiwindup_strat_.legacy_antiwindup = parameter.get_value(); - changed = true; - } else if (param_name == param_prefix_ + "error_deadband") { gains.antiwindup_strat_.error_deadband = parameter.get_value(); diff --git a/control_toolbox/test/pid_ros_parameters_tests.cpp b/control_toolbox/test/pid_ros_parameters_tests.cpp index 6c39f3f5..8346cb55 100644 --- a/control_toolbox/test/pid_ros_parameters_tests.cpp +++ b/control_toolbox/test/pid_ros_parameters_tests.cpp @@ -21,9 +21,6 @@ #include "rclcpp/parameter.hpp" #include "rclcpp/utilities.hpp" -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - using control_toolbox::AntiWindupStrategy; using rclcpp::executors::MultiThreadedExecutor; @@ -58,13 +55,11 @@ void check_set_parameters( const double U_MIN = -10.0; const double TRK_TC = 4.0; const bool SATURATION = true; - const bool ANTIWINDUP = true; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX; ANTIWINDUP_STRAT.i_min = I_MIN; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = ANTIWINDUP; const bool SAVE_I_TERM = true; ASSERT_NO_THROW(pid.initialize_from_args(P, I, D, U_MAX, U_MIN, ANTIWINDUP_STRAT, SAVE_I_TERM)); @@ -99,9 +94,6 @@ void check_set_parameters( ASSERT_TRUE(node->get_parameter(prefix + "saturation", param)); ASSERT_EQ(param.get_value(), SATURATION); - ASSERT_TRUE(node->get_parameter(prefix + "antiwindup", param)); - ASSERT_EQ(param.get_value(), ANTIWINDUP); - ASSERT_TRUE(node->get_parameter(prefix + "antiwindup_strategy", param)); ASSERT_EQ(param.get_value(), ANTIWINDUP_STRAT.to_string()); @@ -118,8 +110,7 @@ void check_set_parameters( ASSERT_EQ(gains.u_max_, U_MAX); ASSERT_EQ(gains.u_min_, U_MIN); ASSERT_EQ(gains.antiwindup_strat_.tracking_time_constant, TRK_TC); - ASSERT_TRUE(gains.antiwindup_); - ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::LEGACY); + ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::NONE); } TEST(PidParametersTest, InitPid_no_prefix) @@ -150,11 +141,10 @@ TEST(PidParametersTest, InitPidTestBadParameter) const double TRK_TC = 4.0; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX_BAD; ANTIWINDUP_STRAT.i_min = I_MIN_BAD; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = false; ASSERT_NO_THROW(pid.initialize_from_args(P, I, D, U_MAX_BAD, U_MIN_BAD, ANTIWINDUP_STRAT, false)); @@ -170,7 +160,6 @@ TEST(PidParametersTest, InitPidTestBadParameter) ASSERT_FALSE(node->get_parameter("u_clamp_min", param)); ASSERT_FALSE(node->get_parameter("tracking_time_constant", param)); ASSERT_FALSE(node->get_parameter("saturation", param)); - ASSERT_FALSE(node->get_parameter("antiwindup", param)); ASSERT_FALSE(node->get_parameter("antiwindup_strategy", param)); // check gains were NOT set @@ -178,13 +167,12 @@ TEST(PidParametersTest, InitPidTestBadParameter) ASSERT_EQ(gains.p_gain_, 0.0); ASSERT_EQ(gains.i_gain_, 0.0); ASSERT_EQ(gains.d_gain_, 0.0); - ASSERT_EQ(gains.i_max_, 0.0); - ASSERT_EQ(gains.i_min_, 0.0); + ASSERT_EQ(gains.i_max_, std::numeric_limits::infinity()); + ASSERT_EQ(gains.i_min_, -std::numeric_limits::infinity()); ASSERT_EQ(gains.u_max_, std::numeric_limits::infinity()); ASSERT_EQ(gains.u_min_, -std::numeric_limits::infinity()); ASSERT_EQ(gains.antiwindup_strat_.tracking_time_constant, 0.0); - ASSERT_FALSE(gains.antiwindup_); - ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::LEGACY); + ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::NONE); } TEST(PidParametersTest, InitPid_param_prefix_only) @@ -247,13 +235,11 @@ TEST(PidParametersTest, SetParametersTest) const double U_MIN = -10.0; const double TRK_TC = 4.0; const bool SATURATION = true; - const bool ANTIWINDUP = true; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX; ANTIWINDUP_STRAT.i_min = I_MIN; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = ANTIWINDUP; const bool SAVE_I_TERM = false; pid.initialize_from_args(P, I, D, U_MAX, U_MIN, ANTIWINDUP_STRAT, SAVE_I_TERM); @@ -284,8 +270,6 @@ TEST(PidParametersTest, SetParametersTest) ASSERT_TRUE(set_result.successful); ASSERT_NO_THROW(set_result = node->set_parameter(rclcpp::Parameter("saturation", SATURATION))); ASSERT_TRUE(set_result.successful); - ASSERT_NO_THROW(set_result = node->set_parameter(rclcpp::Parameter("antiwindup", ANTIWINDUP))); - ASSERT_TRUE(set_result.successful); ASSERT_NO_THROW( set_result = node->set_parameter(rclcpp::Parameter("antiwindup_strategy", ANTIWINDUP_STRAT))); ASSERT_TRUE(set_result.successful); @@ -308,8 +292,7 @@ TEST(PidParametersTest, SetParametersTest) ASSERT_EQ(gains.u_max_, U_MAX); ASSERT_EQ(gains.u_min_, U_MIN); ASSERT_EQ(gains.antiwindup_strat_.tracking_time_constant, TRK_TC); - ASSERT_EQ(gains.antiwindup_, ANTIWINDUP); - ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::LEGACY); + ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::NONE); } TEST(PidParametersTest, SetBadParametersTest) @@ -331,14 +314,12 @@ TEST(PidParametersTest, SetBadParametersTest) const double U_MIN_BAD = 20.0; const double TRK_TC = 4.0; const bool SATURATION = false; - const bool ANTIWINDUP = true; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX; ANTIWINDUP_STRAT.i_min = I_MIN; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = ANTIWINDUP; pid.initialize_from_args(P, I, D, U_MAX, U_MIN, ANTIWINDUP_STRAT, false); @@ -368,8 +349,6 @@ TEST(PidParametersTest, SetBadParametersTest) ASSERT_TRUE(set_result.successful); ASSERT_NO_THROW(set_result = node->set_parameter(rclcpp::Parameter("saturation", SATURATION))); ASSERT_TRUE(set_result.successful); - ASSERT_NO_THROW(set_result = node->set_parameter(rclcpp::Parameter("antiwindup", ANTIWINDUP))); - ASSERT_TRUE(set_result.successful); ASSERT_NO_THROW( set_result = node->set_parameter(rclcpp::Parameter("antiwindup_strategy", ANTIWINDUP_STRAT))); ASSERT_TRUE(set_result.successful); @@ -388,8 +367,7 @@ TEST(PidParametersTest, SetBadParametersTest) ASSERT_EQ(gains.u_max_, std::numeric_limits::infinity()); ASSERT_EQ(gains.u_min_, -std::numeric_limits::infinity()); ASSERT_EQ(gains.antiwindup_strat_.tracking_time_constant, TRK_TC); - ASSERT_EQ(gains.antiwindup_, ANTIWINDUP); - ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::LEGACY); + ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::NONE); // Set the good gains @@ -411,8 +389,7 @@ TEST(PidParametersTest, SetBadParametersTest) ASSERT_EQ(gains.u_max_, std::numeric_limits::infinity()); ASSERT_EQ(gains.u_min_, -std::numeric_limits::infinity()); ASSERT_EQ(gains.antiwindup_strat_.tracking_time_constant, TRK_TC); - ASSERT_EQ(gains.antiwindup_, ANTIWINDUP); - ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::LEGACY); + ASSERT_EQ(gains.antiwindup_strat_, AntiWindupStrategy::NONE); // Now re-enabling it should have the old gains back ASSERT_NO_THROW(set_result = node->set_parameter(rclcpp::Parameter("saturation", true))); @@ -431,8 +408,7 @@ TEST(PidParametersTest, SetBadParametersTest) ASSERT_EQ(updated_gains.u_max_, U_MAX); ASSERT_EQ(updated_gains.u_min_, U_MIN); ASSERT_EQ(updated_gains.antiwindup_strat_.tracking_time_constant, TRK_TC); - ASSERT_EQ(updated_gains.antiwindup_, ANTIWINDUP); - ASSERT_EQ(updated_gains.antiwindup_strat_, AntiWindupStrategy::LEGACY); + ASSERT_EQ(updated_gains.antiwindup_strat_, AntiWindupStrategy::NONE); } TEST(PidParametersTest, GetParametersTest) @@ -451,14 +427,12 @@ TEST(PidParametersTest, GetParametersTest) const double U_MIN = -10.0; const double TRK_TC = 4.0; const bool SATURATION = true; - const bool ANTIWINDUP = true; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX; ANTIWINDUP_STRAT.i_min = I_MIN; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = ANTIWINDUP; ASSERT_FALSE(pid.initialize_from_args(0.0, 0.0, 0.0, 0.0, 0.0, ANTIWINDUP_STRAT, false)) << "Zero u_min and u_max are not valid so initialization should fail"; @@ -495,9 +469,6 @@ TEST(PidParametersTest, GetParametersTest) ASSERT_TRUE(node->get_parameter("saturation", param)); ASSERT_EQ(param.get_value(), SATURATION); - ASSERT_TRUE(node->get_parameter("antiwindup", param)); - ASSERT_EQ(param.get_value(), ANTIWINDUP); - ASSERT_TRUE(node->get_parameter("antiwindup_strategy", param)); ASSERT_EQ(param.get_value(), ANTIWINDUP_STRAT.to_string()); @@ -520,14 +491,12 @@ TEST(PidParametersTest, GetParametersTest) const double U_MAX = 10.0; const double U_MIN = -10.0; const double TRK_TC = 4.0; - const bool ANTIWINDUP = true; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX; ANTIWINDUP_STRAT.i_min = I_MIN; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = ANTIWINDUP; ASSERT_TRUE(pid.initialize_from_args(P, I, D, U_MAX, U_MIN, ANTIWINDUP_STRAT, false)); @@ -548,14 +517,12 @@ TEST(PidParametersTest, GetParametersTest) const double U_MAX = std::numeric_limits::infinity(); const double U_MIN = -std::numeric_limits::infinity(); const double TRK_TC = 4.0; - const bool ANTIWINDUP = true; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX; ANTIWINDUP_STRAT.i_min = I_MIN; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = ANTIWINDUP; ASSERT_FALSE(pid.initialize_from_args(0.0, 0.0, 0.0, 0.0, 0.0, ANTIWINDUP_STRAT, false)) << "Zero u_min and u_max are not valid so initialization should fail"; @@ -591,9 +558,6 @@ TEST(PidParametersTest, GetParametersTest) ASSERT_TRUE(node->get_parameter("saturation", param)); ASSERT_TRUE(param.get_value()) << "Should be enabled by default!"; - ASSERT_TRUE(node->get_parameter("antiwindup", param)); - ASSERT_EQ(param.get_value(), ANTIWINDUP); - ASSERT_TRUE(node->get_parameter("antiwindup_strategy", param)); ASSERT_EQ(param.get_value(), ANTIWINDUP_STRAT.to_string()); @@ -608,7 +572,7 @@ TEST(PidParametersTest, GetParametersFromParams) const bool ACTIVATE_STATE_PUBLISHER = false; TestablePidROS pid(node, "", "", ACTIVATE_STATE_PUBLISHER); - ASSERT_FALSE(pid.initialize_from_ros_parameters()); + ASSERT_TRUE(pid.initialize_from_ros_parameters()); rclcpp::Parameter param_p; ASSERT_TRUE(node->get_parameter("p", param_p)); @@ -624,11 +588,11 @@ TEST(PidParametersTest, GetParametersFromParams) rclcpp::Parameter param_i_clamp_max; ASSERT_TRUE(node->get_parameter("i_clamp_max", param_i_clamp_max)); - EXPECT_TRUE(std::isnan(param_i_clamp_max.get_value())); + ASSERT_TRUE(std::isinf(param_i_clamp_max.get_value())); rclcpp::Parameter param_i_clamp_min; ASSERT_TRUE(node->get_parameter("i_clamp_min", param_i_clamp_min)); - EXPECT_TRUE(std::isnan(param_i_clamp_min.get_value())); + ASSERT_TRUE(std::isinf(param_i_clamp_min.get_value())); rclcpp::Parameter param_u_clamp_max; ASSERT_TRUE(node->get_parameter("u_clamp_max", param_u_clamp_max)); @@ -667,11 +631,10 @@ TEST(PidParametersTest, MultiplePidInstances) const double U_MIN = -10.0; const double TRK_TC = 4.0; AntiWindupStrategy ANTIWINDUP_STRAT; - ANTIWINDUP_STRAT.type = AntiWindupStrategy::LEGACY; + ANTIWINDUP_STRAT.type = AntiWindupStrategy::NONE; ANTIWINDUP_STRAT.i_max = I_MAX; ANTIWINDUP_STRAT.i_min = I_MIN; ANTIWINDUP_STRAT.tracking_time_constant = TRK_TC; - ANTIWINDUP_STRAT.legacy_antiwindup = false; ASSERT_NO_THROW(pid_1.initialize_from_args(P, I, D, U_MAX, U_MIN, ANTIWINDUP_STRAT, false)); ASSERT_NO_THROW(pid_2.initialize_from_args(2 * P, I, D, U_MAX, U_MIN, ANTIWINDUP_STRAT, false)); @@ -691,5 +654,3 @@ int main(int argc, char ** argv) rclcpp::shutdown(); return result; } - -#pragma GCC diagnostic pop diff --git a/control_toolbox/test/pid_ros_publisher_tests.cpp b/control_toolbox/test/pid_ros_publisher_tests.cpp index c434587f..1274c291 100644 --- a/control_toolbox/test/pid_ros_publisher_tests.cpp +++ b/control_toolbox/test/pid_ros_publisher_tests.cpp @@ -27,9 +27,6 @@ #include "rclcpp/utilities.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - using control_toolbox::AntiWindupStrategy; using PidStateMsg = control_msgs::msg::PidState; using rclcpp::executors::MultiThreadedExecutor; @@ -44,10 +41,9 @@ TEST(PidPublisherTest, PublishTest) control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "", true); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = 5.0; antiwindup_strat.i_min = -5.0; - antiwindup_strat.legacy_antiwindup = false; antiwindup_strat.tracking_time_constant = 1.0; pid_ros.initialize_from_args(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat, false); @@ -60,7 +56,7 @@ TEST(PidPublisherTest, PublishTest) "/pid_state", rclcpp::SensorDataQoS(), state_callback); double command = pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0)); - EXPECT_EQ(-1.5, command); + EXPECT_EQ(-1.0, command); // wait for callback for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i) @@ -83,10 +79,9 @@ TEST(PidPublisherTest, PublishTest_start_deactivated) control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "", false); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = 5.0; antiwindup_strat.i_min = -5.0; - antiwindup_strat.legacy_antiwindup = false; antiwindup_strat.tracking_time_constant = 1.0; pid_ros.initialize_from_args(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat, false); @@ -99,7 +94,7 @@ TEST(PidPublisherTest, PublishTest_start_deactivated) "/pid_state", rclcpp::SensorDataQoS(), state_callback); double command = pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0)); - EXPECT_EQ(-1.5, command); + EXPECT_EQ(-1.0, command); // wait for callback for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i) @@ -153,10 +148,9 @@ TEST(PidPublisherTest, PublishTest_prefix) control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "global", true); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = 5.0; antiwindup_strat.i_min = -5.0; - antiwindup_strat.legacy_antiwindup = false; antiwindup_strat.tracking_time_constant = 1.0; pid_ros.initialize_from_args(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat, false); @@ -169,7 +163,7 @@ TEST(PidPublisherTest, PublishTest_prefix) "/global/pid_state", rclcpp::SensorDataQoS(), state_callback); double command = pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0)); - EXPECT_EQ(-1.5, command); + EXPECT_EQ(-1.0, command); // wait for callback for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i) @@ -192,10 +186,9 @@ TEST(PidPublisherTest, PublishTest_local_prefix) control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node, "", "~/local/", true); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = 5.0; antiwindup_strat.i_min = -5.0; - antiwindup_strat.legacy_antiwindup = false; antiwindup_strat.tracking_time_constant = 1.0; pid_ros.initialize_from_args(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat, false); @@ -208,7 +201,7 @@ TEST(PidPublisherTest, PublishTest_local_prefix) "~/local/pid_state", rclcpp::SensorDataQoS(), state_callback); double command = pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0)); - EXPECT_EQ(-1.5, command); + EXPECT_EQ(-1.0, command); // wait for callback for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i) @@ -235,10 +228,9 @@ TEST(PidPublisherTest, PublishTestLifecycle) pid_ros.get_pid_state_publisher()); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = 5.0; antiwindup_strat.i_min = -5.0; - antiwindup_strat.legacy_antiwindup = false; antiwindup_strat.tracking_time_constant = 1.0; pid_ros.initialize_from_args(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat, false); @@ -251,7 +243,7 @@ TEST(PidPublisherTest, PublishTestLifecycle) "/pid_state", rclcpp::SensorDataQoS(), state_callback); double command = pid_ros.compute_command(-0.5, rclcpp::Duration(1, 0)); - EXPECT_EQ(-1.5, command); + EXPECT_EQ(-1.0, command); // wait for callback for (size_t i = 0; i < ATTEMPTS && !callback_called; ++i) @@ -273,5 +265,3 @@ int main(int argc, char ** argv) rclcpp::shutdown(); return result; } - -#pragma GCC diagnostic pop diff --git a/control_toolbox/test/pid_tests.cpp b/control_toolbox/test/pid_tests.cpp index 868674d6..5629cd5f 100644 --- a/control_toolbox/test/pid_tests.cpp +++ b/control_toolbox/test/pid_tests.cpp @@ -38,9 +38,6 @@ #include "gmock/gmock.h" -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - using control_toolbox::AntiWindupStrategy; using control_toolbox::Pid; using namespace std::chrono_literals; @@ -54,7 +51,7 @@ TEST(ParameterTest, UTermBadIBoundsTestConstructor) // Pid(double p, double i, double d, double u_max, double u_min, // AntiWindupStrategy antiwindup_strat); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = 1.0; antiwindup_strat.i_min = -1.0; EXPECT_THROW(Pid pid(1.0, 1.0, 1.0, -1.0, 1.0, antiwindup_strat), std::invalid_argument); @@ -69,7 +66,7 @@ TEST(ParameterTest, UTermBadIBoundsTest) // Pid(double p, double i, double d, double u_max, double u_min, // AntiWindupStrategy antiwindup_strat); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = 1.0; antiwindup_strat.i_min = -1.0; Pid pid(1.0, 1.0, 1.0, 1.0, -1.0, antiwindup_strat); @@ -91,7 +88,7 @@ TEST(ParameterTest, outputClampTest) // Pid(double p, double i, double d, double u_max, double u_min, // AntiWindupStrategy antiwindup_strat); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::BACK_CALCULATION; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.tracking_time_constant = 0.0; // Set to 0.0 to use the default value // Setting u_max = 1.0 and u_min = -1.0 to test clamping Pid pid(1.0, 0.0, 0.0, 1.0, -1.0, antiwindup_strat); @@ -147,7 +144,7 @@ TEST(ParameterTest, noOutputClampTest) // Pid(double p, double i, double d, double u_max, double u_min, // AntiWindupStrategy antiwindup_strat); AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::BACK_CALCULATION; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.tracking_time_constant = 0.0; // Set to 0.0 to use the default value // Setting u_max = INF and u_min = -INF to disable clamping Pid pid( @@ -208,6 +205,8 @@ TEST(ParameterTest, integrationBackCalculationZeroGainTest) // AntiWindupStrategy antiwindup_strat); AntiWindupStrategy antiwindup_strat; antiwindup_strat.type = AntiWindupStrategy::BACK_CALCULATION; + antiwindup_strat.i_max = 1.0; + antiwindup_strat.i_min = -1.0; antiwindup_strat.tracking_time_constant = 0.0; // Set to 0.0 to use the default value Pid pid(0.0, 0.0, 0.0, 20.0, -20.0, antiwindup_strat); @@ -258,6 +257,8 @@ TEST(ParameterTest, integrationConditionalIntegrationZeroGainTest) // AntiWindupStrategy antiwindup_strat); AntiWindupStrategy antiwindup_strat; antiwindup_strat.type = AntiWindupStrategy::CONDITIONAL_INTEGRATION; + antiwindup_strat.i_max = 1.0; + antiwindup_strat.i_min = -1.0; Pid pid(0.0, 0.0, 0.0, 20.0, -20.0, antiwindup_strat); double cmd = 0.0; @@ -296,81 +297,28 @@ TEST(ParameterTest, integrationConditionalIntegrationZeroGainTest) EXPECT_EQ(0.0, cmd); } -TEST(ParameterTest, ITermBadIBoundsTestConstructor) -{ - RecordProperty( - "description", - "This test checks if an error is thrown for bad i_bounds specification (i.e. " - "i_min > i_max)."); - - // Check that the output is not a non-sense if i-bounds are bad, i.e. i_min > i_max - EXPECT_THROW(Pid pid(1.0, 1.0, 1.0, -1.0, 1.0), std::invalid_argument); -} - TEST(ParameterTest, ITermBadIBoundsTest) { RecordProperty( "description", - "This test checks if gains remain for bad i_bounds specification (i.e. " - "i_min > i_max)."); + "This test checks if gains remain for bad i_bounds specification (i.e. i_min > i_max)."); - Pid pid(1.0, 1.0, 1.0, 1.0, -1.0); + AntiWindupStrategy antiwindup_strat; + antiwindup_strat.type = AntiWindupStrategy::NONE; + antiwindup_strat.i_max = 1.0; + antiwindup_strat.i_min = -1.0; + + Pid pid(1.0, 1.0, 1.0, 1.0, -1.0, antiwindup_strat); auto gains = pid.get_gains(); - EXPECT_DOUBLE_EQ(gains.antiwindup_strat_.i_min, -1.0); EXPECT_DOUBLE_EQ(gains.antiwindup_strat_.i_max, 1.0); + EXPECT_DOUBLE_EQ(gains.antiwindup_strat_.i_min, -1.0); // Try to set bad i-bounds, i.e. i_min > i_max - EXPECT_NO_THROW(pid.set_gains(1.0, 1.0, 1.0, -2.0, 2.0)); + antiwindup_strat.i_max = -1.0; + antiwindup_strat.i_min = 1.0; + EXPECT_NO_THROW(pid.set_gains(1.0, 1.0, 1.0, 1.0, -1.0, antiwindup_strat)); // Check if gains were not updated because i-bounds are bad, i.e. i_min > i_max - EXPECT_DOUBLE_EQ(gains.antiwindup_strat_.i_min, -1.0); EXPECT_DOUBLE_EQ(gains.antiwindup_strat_.i_max, 1.0); -} - -TEST(ParameterTest, integrationClampTest) -{ - RecordProperty( - "description", - "This test succeeds if the integral contribution is clamped when the integral gain is " - "non-zero."); - - Pid pid(0.0, 1.0, 0.0, 1.0, -1.0); - - double cmd = 0.0; - - // Test lower limit - cmd = pid.compute_command(-10.03, 1.0); - EXPECT_EQ(-1.0, cmd); - - // Test upper limit - cmd = pid.compute_command(30.0, 1.0); - EXPECT_EQ(1.0, cmd); -} - -TEST(ParameterTest, integrationClampZeroGainTest) -{ - RecordProperty( - "description", - "This test succeeds if the integral contribution is clamped when the integral gain is zero. If " - "the integral contribution is not clamped while it is disabled, it can cause sudden jumps to " - "the minimum or maximum bound in control command when re-enabled."); - - double i_gain = 0.0; - double i_min = -1.0; - double i_max = 1.0; - Pid pid(0.0, i_gain, 0.0, i_max, i_min); - - double cmd = 0.0; - double pe, ie, de; - - cmd = pid.compute_command(-1.0, 1.0); - pid.get_current_pid_errors(pe, ie, de); - EXPECT_LE(i_min, cmd); - EXPECT_LE(cmd, i_max); - EXPECT_EQ(0.0, cmd); - - cmd = pid.compute_command(-1.0, 1.0); - EXPECT_LE(i_min, cmd); - EXPECT_LE(cmd, i_max); - EXPECT_EQ(0.0, cmd); + EXPECT_DOUBLE_EQ(gains.antiwindup_strat_.i_min, -1.0); } constexpr double EPS = 1e-9; @@ -381,49 +329,30 @@ TEST(ParameterTest, integrationAntiwindupTest) "This test succeeds if the integral error is prevented from winding up when i_gain > 0"); double i_gain = 2.0; - double i_min = -1.0; - double i_max = 1.0; - Pid pid(0.0, i_gain, 0.0, i_max, i_min, true); + + AntiWindupStrategy antiwindup_strat; + antiwindup_strat.type = AntiWindupStrategy::BACK_CALCULATION; + antiwindup_strat.i_max = 1.0; + antiwindup_strat.i_min = -1.0; + antiwindup_strat.tracking_time_constant = 1.0; + const double u_max = std::numeric_limits::infinity(); + const double u_min = -std::numeric_limits::infinity(); + + Pid pid(0.0, i_gain, 0.0, u_max, u_min, antiwindup_strat); double cmd = 0.0; cmd = pid.compute_command(-1.0, 1.0); - EXPECT_NEAR(-1.0, cmd, EPS); + EXPECT_NEAR(0.0, cmd, EPS); cmd = pid.compute_command(-1.0, 1.0); EXPECT_NEAR(-1.0, cmd, EPS); cmd = pid.compute_command(0.5, 1.0); - EXPECT_NEAR(0.0, cmd, EPS); - - cmd = pid.compute_command(-1.0, 1.0); EXPECT_NEAR(-1.0, cmd, EPS); -} - -TEST(ParameterTest, negativeIntegrationAntiwindupTest) -{ - RecordProperty( - "description", - "This test succeeds if the integral error is prevented from winding up when i_gain < 0"); - - double i_gain = -2.5; - double i_min = -0.2; - double i_max = 0.5; - Pid pid(0.0, i_gain, 0.0, i_max, i_min, true); - - double cmd = 0.0; - - cmd = pid.compute_command(0.1, 1.0); - EXPECT_NEAR(-0.2, cmd, EPS); - - cmd = pid.compute_command(0.1, 1.0); - EXPECT_NEAR(-0.2, cmd, EPS); - - cmd = pid.compute_command(-0.05, 1.0); - EXPECT_NEAR(-0.075, cmd, EPS); - cmd = pid.compute_command(0.1, 1.0); - EXPECT_NEAR(-0.2, cmd, EPS); + cmd = pid.compute_command(0.0, 1.0); + EXPECT_NEAR(0.0, cmd, EPS); } TEST(ParameterTest, gainSettingCopyPIDTest) @@ -442,13 +371,11 @@ TEST(ParameterTest, gainSettingCopyPIDTest) double u_max = std::numeric_limits::infinity(); double u_min = -1 * u_max; double tracking_time_constant = std::rand() % 100; - bool antiwindup = false; AntiWindupStrategy antiwindup_strat; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = i_max; antiwindup_strat.i_min = i_min; antiwindup_strat.tracking_time_constant = tracking_time_constant; - antiwindup_strat.legacy_antiwindup = antiwindup; // Initialize the default way Pid pid1(p_gain, i_gain, d_gain, u_max, u_min, antiwindup_strat); @@ -469,7 +396,6 @@ TEST(ParameterTest, gainSettingCopyPIDTest) EXPECT_EQ(tracking_time_constant, antiwindup_strat_return.tracking_time_constant); EXPECT_EQ(i_min, antiwindup_strat_return.i_min); EXPECT_EQ(i_max, antiwindup_strat_return.i_max); - EXPECT_EQ(antiwindup, antiwindup_strat_return.legacy_antiwindup); EXPECT_EQ(antiwindup_strat.to_string(), antiwindup_strat_return.to_string()); // Test return values using struct ------------------------------------------------- @@ -483,12 +409,10 @@ TEST(ParameterTest, gainSettingCopyPIDTest) u_max = std::numeric_limits::infinity(); u_min = -1 * u_max; tracking_time_constant = std::rand() % 100; - antiwindup = false; - antiwindup_strat.type = AntiWindupStrategy::LEGACY; + antiwindup_strat.type = AntiWindupStrategy::NONE; antiwindup_strat.i_max = i_max; antiwindup_strat.i_min = i_min; antiwindup_strat.tracking_time_constant = tracking_time_constant; - antiwindup_strat.legacy_antiwindup = antiwindup; pid1.set_gains(p_gain, i_gain, d_gain, u_max, u_min, antiwindup_strat); @@ -500,11 +424,9 @@ TEST(ParameterTest, gainSettingCopyPIDTest) EXPECT_EQ(i_min, g1.i_min_); EXPECT_EQ(u_max, g1.u_max_); EXPECT_EQ(u_min, g1.u_min_); - EXPECT_EQ(antiwindup, g1.antiwindup_); EXPECT_EQ(tracking_time_constant, g1.antiwindup_strat_.tracking_time_constant); EXPECT_EQ(i_max, g1.antiwindup_strat_.i_max); EXPECT_EQ(i_min, g1.antiwindup_strat_.i_min); - EXPECT_EQ(antiwindup, g1.antiwindup_strat_.legacy_antiwindup); EXPECT_EQ(antiwindup_strat.to_string(), g1.antiwindup_strat_.to_string()); // Send update command to populate errors ------------------------------------------------- @@ -528,7 +450,6 @@ TEST(ParameterTest, gainSettingCopyPIDTest) EXPECT_EQ(tracking_time_constant, g1.antiwindup_strat_.tracking_time_constant); EXPECT_EQ(antiwindup_strat_return.i_max, g1.antiwindup_strat_.i_max); EXPECT_EQ(antiwindup_strat_return.i_min, g1.antiwindup_strat_.i_min); - EXPECT_EQ(antiwindup, g1.antiwindup_strat_.legacy_antiwindup); EXPECT_EQ(antiwindup_strat.to_string(), g1.antiwindup_strat_.to_string()); // Test that errors are zero @@ -556,7 +477,6 @@ TEST(ParameterTest, gainSettingCopyPIDTest) EXPECT_EQ(tracking_time_constant, g1.antiwindup_strat_.tracking_time_constant); EXPECT_EQ(antiwindup_strat_return.i_max, g1.antiwindup_strat_.i_max); EXPECT_EQ(antiwindup_strat_return.i_min, g1.antiwindup_strat_.i_min); - EXPECT_EQ(antiwindup, g1.antiwindup_strat_.legacy_antiwindup); EXPECT_EQ(antiwindup_strat.to_string(), g1.antiwindup_strat_.to_string()); // Test that errors are zero @@ -586,8 +506,11 @@ TEST(CommandTest, proportionalOnlyTest) "This test checks that a command is computed correctly using the proportional contribution " "only."); + AntiWindupStrategy antiwindup_strat; + antiwindup_strat.type = AntiWindupStrategy::NONE; + // Set only proportional gain - Pid pid(1.0, 0.0, 0.0, 0.0, 0.0); + Pid pid(1.0, 0.0, 0.0, 10.0, -10.0, antiwindup_strat); double cmd = 0.0; // If initial error = 0, p-gain = 1, dt = 1 @@ -618,62 +541,66 @@ TEST(CommandTest, integralOnlyTest) "This test checks that a command is computed correctly using the integral contribution only " "(ATTENTION: this test depends on the integration scheme)."); + AntiWindupStrategy antiwindup_strat; + antiwindup_strat.type = AntiWindupStrategy::NONE; + // Set only integral gains with enough limits to test behavior - Pid pid(0.0, 1.0, 0.0, 5.0, -5.0); + Pid pid(0.0, 1.0, 0.0, 5.0, -5.0, antiwindup_strat); double cmd = 0.0; // If initial error = 0, i-gain = 1, dt = 1 cmd = pid.compute_command(-0.5, 1.0); - // Then expect command = error - EXPECT_EQ(-0.5, cmd); + // Then expect command = 0.0 + EXPECT_EQ(0.0, cmd); // If call again with same arguments cmd = pid.compute_command(-0.5, 1.0); - // Then expect the integral part to double the command - EXPECT_EQ(-1.0, cmd); + // Then expect the integral term to match the previous error + EXPECT_EQ(-0.5, cmd); // Call again with no error cmd = pid.compute_command(0.0, 1.0); - // Expect the integral part to keep the previous command because it ensures error = 0 + // Expect the integral term to be the sum of the two previous errors EXPECT_EQ(-1.0, cmd); - // Double check that the integral contribution keep the previous command + // Check that the integral contribution keep the previous command cmd = pid.compute_command(0.0, 1.0); EXPECT_EQ(-1.0, cmd); // Finally call again with positive error to see if the command changes in the opposite direction cmd = pid.compute_command(1.0, 1.0); - // Expect that the command is cleared since error = -1 * previous command, i-gain = 1, dt = 1 - EXPECT_EQ(0.0, cmd); + // Expect that the command is -1.0 + EXPECT_EQ(-1.0, cmd); // If initial error = 0, i-gain = 1, dt = 1 - cmd = pid.compute_command(-0.5, 1.0); - // Then expect command = error - EXPECT_EQ(-0.5, cmd); + cmd = pid.compute_command(0.0, 1.0); + // Then expect command = -1.0 +1.0 = 0.0 + EXPECT_EQ(0.0, cmd); // after reset without argument (save_i_term=false) // we expect the command to be 0 if update is called error = 0 pid.reset(); - cmd = pid.compute_command(0.0, 1.0); + cmd = pid.compute_command(0.5, 1.0); EXPECT_EQ(0.0, cmd); // If initial error = 0, i-gain = 1, dt = 1 - cmd = pid.compute_command(-0.5, 1.0); - // Then expect command = error - EXPECT_EQ(-0.5, cmd); + cmd = pid.compute_command(0.0, 1.0); + // Then expect command = 0.5 + EXPECT_EQ(0.5, cmd); // after reset with argument (save_i_term=false) // we expect the command to be 0 if update is called error = 0 pid.reset(false); - cmd = pid.compute_command(0.0, 1.0); + cmd = pid.compute_command(-0.5, 1.0); EXPECT_EQ(0.0, cmd); // If initial error = 0, i-gain = 1, dt = 1 - cmd = pid.compute_command(-0.5, 1.0); - // Then expect command = error + cmd = pid.compute_command(0.0, 1.0); + // Then expect command = -0.5 EXPECT_EQ(-0.5, cmd); // after reset with save_i_term=true // we expect still the same command if update is called error = 0 pid.reset(true); cmd = pid.compute_command(0.0, 1.0); + // Then expect command = -0.5 EXPECT_EQ(-0.5, cmd); } @@ -684,8 +611,11 @@ TEST(CommandTest, derivativeOnlyTest) "This test checks that a command is computed correctly using the derivative contribution only " "with own differentiation (ATTENTION: this test depends on the differentiation scheme)."); + AntiWindupStrategy antiwindup_strat; + antiwindup_strat.type = AntiWindupStrategy::NONE; + // Set only derivative gain - Pid pid(0.0, 0.0, 1.0, 0.0, 0.0); + Pid pid(0.0, 0.0, 1.0, 10.0, -10.0, antiwindup_strat); double cmd = 0.0; // If initial error = 0, d-gain = 1, dt = 1 @@ -721,24 +651,29 @@ TEST(CommandTest, completePIDTest) "This test checks that a command is computed correctly using a complete PID controller " "(ATTENTION: this test depends on the integral and differentiation schemes)."); - Pid pid(1.0, 1.0, 1.0, 5.0, -5.0); + AntiWindupStrategy antiwindup_strat; + antiwindup_strat.type = AntiWindupStrategy::NONE; + antiwindup_strat.i_max = 10.0; + antiwindup_strat.i_min = -10.0; + + Pid pid(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat); double cmd = 0.0; // All contributions are tested, here few tests check that they sum up correctly // If initial error = 0, all gains = 1, dt = 1 cmd = pid.compute_command(-0.5, 1.0); - // Then expect command = 3x error - EXPECT_EQ(-1.5, cmd); + // Then expect command = -1.0 + EXPECT_EQ(-1.0, cmd); // If call again with same arguments, no error change, but integration do its part cmd = pid.compute_command(-0.5, 1.0); - // Then expect command = 3x error again - EXPECT_EQ(-1.5, cmd); + // Then expect command = -1.0 + EXPECT_EQ(-1.0, cmd); // If call again increasing the error - cmd = pid.compute_command(-1.0, 1.0); - // Then expect command equals to p = -1, i = -2.0 (i.e. - 0.5 - 0.5 - 1.0), d = -0.5 - EXPECT_EQ(-3.5, cmd); + cmd = pid.compute_command(0.0, 1.0); + // Then expect command equals to p = 0, i = -1.0 (i.e. - 0.5 - 0.5), d = 0.5, cmd = -0.5 + EXPECT_EQ(-0.5, cmd); } TEST(CommandTest, backCalculationPIDTest) @@ -753,6 +688,8 @@ TEST(CommandTest, backCalculationPIDTest) // Setting u_max = 5.0 and u_min = -5.0 to test clamping AntiWindupStrategy antiwindup_strat; antiwindup_strat.type = AntiWindupStrategy::BACK_CALCULATION; + antiwindup_strat.i_max = 10.0; + antiwindup_strat.i_min = -10.0; antiwindup_strat.tracking_time_constant = 1.0; // Set to 0.0 to use the default value Pid pid(0.0, 1.0, 0.0, 5.0, -5.0, antiwindup_strat); @@ -814,6 +751,8 @@ TEST(CommandTest, conditionalIntegrationPIDTest) // Setting u_max = 5.0 and u_min = -5.0 to test clamping AntiWindupStrategy antiwindup_strat; antiwindup_strat.type = AntiWindupStrategy::CONDITIONAL_INTEGRATION; + antiwindup_strat.i_max = 10.0; + antiwindup_strat.i_min = -10.0; antiwindup_strat.tracking_time_constant = 1.0; Pid pid(0.0, 1.0, 0.0, 5.0, -5.0, antiwindup_strat); @@ -867,10 +806,16 @@ TEST(CommandTest, timeArgumentTest) { RecordProperty("description", "Tests different dt argument type methods."); - Pid pid1(1.0, 1.0, 1.0, 5.0, -5.0); - Pid pid2(1.0, 1.0, 1.0, 5.0, -5.0); - Pid pid3(1.0, 1.0, 1.0, 5.0, -5.0); - Pid pid4(1.0, 1.0, 1.0, 5.0, -5.0); + AntiWindupStrategy antiwindup_strat; + antiwindup_strat.type = AntiWindupStrategy::NONE; + antiwindup_strat.i_max = 10.0; + antiwindup_strat.i_min = -10.0; + antiwindup_strat.tracking_time_constant = 1.0; + + Pid pid1(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat); + Pid pid2(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat); + Pid pid3(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat); + Pid pid4(1.0, 1.0, 1.0, 5.0, -5.0, antiwindup_strat); // call without error_dt, dt is used to calculate error_dt auto cmd1 = pid1.compute_command(-0.5, 1.0); @@ -881,7 +826,7 @@ TEST(CommandTest, timeArgumentTest) // If initial error = 0, all gains = 1, dt = 1 // Then expect command = 3x error - EXPECT_EQ(-1.5, cmd1); + EXPECT_EQ(-1.0, cmd1); EXPECT_EQ(cmd1, cmd2); EXPECT_EQ(cmd1, cmd3); EXPECT_EQ(cmd1, cmd4); @@ -891,7 +836,7 @@ TEST(CommandTest, timeArgumentTest) cmd2 = pid2.compute_command(-0.5, 0.0, dt); cmd3 = pid3.compute_command(-0.5, 0.0, dt.nanoseconds()); cmd4 = pid4.compute_command(-0.5, 0.0, std::chrono::nanoseconds(1s)); - EXPECT_EQ(-1.5, cmd1); + EXPECT_EQ(-1.0, cmd1); EXPECT_EQ(cmd1, cmd2); EXPECT_EQ(cmd1, cmd3); EXPECT_EQ(cmd1, cmd4); @@ -899,7 +844,7 @@ TEST(CommandTest, timeArgumentTest) cmd2 = pid2.compute_command(-0.5, 0.0, dt); cmd3 = pid3.compute_command(-0.5, 0.0, dt.nanoseconds()); cmd4 = pid4.compute_command(-0.5, 0.0, std::chrono::nanoseconds(1s)); - EXPECT_EQ(-2.0, cmd1); + EXPECT_EQ(-1.5, cmd1); EXPECT_EQ(cmd1, cmd2); EXPECT_EQ(cmd1, cmd3); EXPECT_EQ(cmd1, cmd4); @@ -909,7 +854,7 @@ TEST(CommandTest, timeArgumentTest) pid1.get_current_pid_errors(pe, ie1, de); cmd1 = pid1.compute_command(-0.5, 0.0, 0.0); pid1.get_current_pid_errors(pe, ie2, de); - EXPECT_EQ(-2.0, cmd1); + EXPECT_EQ(-1.5, cmd1); EXPECT_EQ(ie1, ie2); // should throw if called with negative dt EXPECT_THROW(cmd1 = pid1.compute_command(-0.5, 0.0, -1.0), std::invalid_argument); @@ -933,5 +878,3 @@ int main(int argc, char ** argv) testing::InitGoogleMock(&argc, argv); return RUN_ALL_TESTS(); } - -#pragma GCC diagnostic pop