Skip to content

Remove legacy and deprecated PID parameters #436

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 5 commits into
base: ros2-master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
230 changes: 26 additions & 204 deletions control_toolbox/include/control_toolbox/pid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
*/
Expand All @@ -75,16 +70,14 @@ struct AntiWindupStrategy
{
UNDEFINED = -1,
NONE,
LEGACY,
BACK_CALCULATION,
CONDITIONAL_INTEGRATION
};

AntiWindupStrategy()
: type(UNDEFINED),
i_min(std::numeric_limits<double>::quiet_NaN()),
i_max(std::numeric_limits<double>::quiet_NaN()),
legacy_antiwindup(false),
: type(NONE),
i_max(std::numeric_limits<double>::infinity()),
i_min(-std::numeric_limits<double>::infinity()),
tracking_time_constant(0.0),
error_deadband(std::numeric_limits<double>::epsilon())
{
Expand All @@ -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;
Expand All @@ -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'.");
}
}
Expand All @@ -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)))
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
if (type != NONE && ((i_min > i_max) || !std::isfinite(i_min) || !std::isfinite(i_max)))
if ((i_min > i_max) && ( !std::isfinite(i_min) || !std::isfinite(i_max)))

i_min and i_max is valid for all integration/antiwindup techniques?

{
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: {})",
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
"AntiWindupStrategy requires i_min < i_max and to be finite (i_min: {}, i_max: {})",
"PID requires i_min < i_max if limits are 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");
Expand All @@ -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:
Expand All @@ -182,10 +158,8 @@ struct AntiWindupStrategy
}

Value type = UNDEFINED;
double i_min = std::numeric_limits<double>::quiet_NaN(); /**< Minimum allowable integral term. */
double i_max = std::numeric_limits<double>::quiet_NaN(); /**< Maximum allowable integral term. */

bool legacy_antiwindup = false; /**< Use legacy anti-windup strategy. */
double i_max = std::numeric_limits<double>::infinity(); /**< Maximum allowable integral term. */
double i_min = -std::numeric_limits<double>::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.
Expand Down Expand Up @@ -265,8 +239,8 @@ inline bool is_zero(T value, T tolerance = std::numeric_limits<T>::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();
Expand All @@ -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<double>::infinity()),
u_min_(-std::numeric_limits<double>::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<double>::infinity()),
u_min_(-std::numeric_limits<double>::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.
*
Expand All @@ -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))
Expand Down Expand Up @@ -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<double>::infinity(); /**< Maximum allowable integral term. */
double i_min_ =
-std::numeric_limits<double>::infinity(); /**< Minimum allowable integral term. */
double u_max_ = std::numeric_limits<double>::infinity(); /**< Maximum allowable output. */
double u_min_ = -std::numeric_limits<double>::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.
*
Expand All @@ -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<double>::infinity(),
double u_min = -std::numeric_limits<double>::infinity(),
const AntiWindupStrategy & antiwindup_strat = AntiWindupStrategy());

/*!
* \brief Copy constructor required for preventing mutexes from being copied
Expand All @@ -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.
*
Expand All @@ -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.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what about i_min > i_max?

*/
bool initialize(
double p, double i, double d, double u_max, double u_min,
Expand All @@ -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.
Expand Down Expand Up @@ -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.
*
Expand All @@ -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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what about i_min > i_max?

* \note This method is not RT safe
*/
bool set_gains(
Expand Down
Loading
Loading