Class PidROS
Defined in File pid_ros.hpp
Class Documentation
-
class PidROS
Public Functions
Constructor of PidROS class.
The node is passed to this class to handler the ROS parameters, this class allows to add a prefix to the pid parameters
- Parameters:
node – ROS node
prefix – prefix to add to the pid parameters. Per default is prefix interpreted as prefix for topics.
prefix_is_for_params – provided prefix should be interpreted as prefix for parameters. If the parameter is
truethen “/” in the middle of the string will not be replaced with “.” for parameters prefix. “/” or “~/” at the beginning will be removed.
-
void initialize_from_args(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Initialize the PID controller and set the parameters.
Note
New gains are not applied if i_min_ > i_max_
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
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.
-
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Initialize the PID controller and set the parameters.
Note
New gains are not applied if i_min_ > i_max_
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
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.
-
void initialize_from_args(double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term)
Initialize the PID controller and set the parameters.
Note
New gains are not applied if i_min_ > i_max_
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – The max integral windup.
i_min – The min integral windup.
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.
save_i_term – save integrator output between resets.
-
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term)
Initialize the PID controller and set the parameters.
Note
New gains are not applied if i_min_ > i_max_
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – The max integral windup.
i_min – The min integral windup.
antiwindup – antiwindup.
save_i_term – save integrator output between resets.
-
void initialize_from_args(double p, double i, double d, double i_max, double i_min, double u_max, double u_min, double trk_tc, bool saturation, bool antiwindup, AntiwindupStrategy antiwindup_strat, bool save_i_term)
Initialize the PID controller and set the parameters.
- Deprecated:
{only when
antiwindup_strat == AntiwindupStrategy::NONE:} Old anti-windup technique is deprecated and will be removed by the ROS 2 Kilted Kaiju release.
Note
New gains are not applied if i_min_ > i_max_ or if u_min_ > u_max_.
Warning
{If you pass
AntiwindupStrategy::NONE, at runtime a warning will be printed:}"Old anti-windup technique is deprecated. This option will be removed by the ROS 2 Kilted Kaiju release."- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – The max integral windup.
i_min – The min integral windup.
antiwindup – antiwindup.
save_i_term – save integrator output between resets.
u_max – Upper output clamp.
u_min – Lower output clamp.
trk_tc – 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.
saturation – Enables output saturation. When true, the controller output is clamped between u_max and u_min.
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.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior. When a strategy other than ‘none’ is selected, it will override the controller’s default anti-windup behavior.
save_i_term – save integrator output between resets.
-
void initialize_from_args(double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation, AntiwindupStrategy antiwindup_strat, bool save_i_term)
Initialize the PID controller and set the parameters.
Note
New gains are not applied if u_min_ > u_max_.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
u_max – Upper output clamp.
u_min – Lower output clamp.
trk_tc – 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.
saturation – Enables output saturation. When true, the controller output is clamped between u_max and u_min.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
save_i_term – save integrator output between resets.
-
bool initialize_from_ros_parameters()
Initialize the PID controller based on already set parameters.
- Returns:
True if all parameters are set (p, i, d, i_max, i_min, u_max, u_min and trk_tc), False otherwise
-
bool initPid()
Initialize the PID controller based on already set parameters.
- Returns:
True if all parameters are set (p, i, d, i_min and i_max), False otherwise
-
void reset()
Reset the state of this PID controller.
Note
save_i_term parameter is read from ROS parameters
-
void reset(bool save_i_term)
Reset the state of this PID controller.
- Parameters:
save_i_term – boolean indicating if integral term is retained on reset()
-
double compute_command(double error, const rclcpp::Duration &dt)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep
dt.- Parameters:
error – Error since last call (error = target - state)
dt – Change in time since last call in seconds
- Returns:
PID command
-
double computeCommand(double error, rclcpp::Duration dt)
Set the PID error and compute the PID command with nonuniform time step size. The derivative error is computed from the change in the error and the timestep
dt.- Parameters:
error – Error since last call (error = target - state)
dt – Change in time since last call in seconds
- Returns:
PID command
-
double compute_command(double error, double error_dot, const rclcpp::Duration &dt)
Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt since last call
dt – Change in time since last call in seconds
- Returns:
PID command
-
double computeCommand(double error, double error_dot, rclcpp::Duration dt)
Set the PID error and compute the PID command with nonuniform time step size. This also allows the user to pass in a precomputed derivative error.
- Parameters:
error – Error since last call (error = target - state)
error_dot – d(Error)/dt since last call
dt – Change in time since last call in seconds
- Returns:
PID command
-
Pid::Gains get_gains()
Get PID gains for the controller.
- Returns:
gains A struct of the PID gain values
-
Pid::Gains getGains()
Get PID gains for the controller.
- Returns:
gains A struct of the PID gain values
-
void set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false)
Set PID gains for the controller.
Note
New gains are not applied if i_min > i_max
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
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.
-
void set_gains(double p, double i, double d, double i_max, double i_min, double u_max, double u_min, double trk_tc = 0.0, bool saturation = false, bool antiwindup = false, AntiwindupStrategy antiwindup_strat = AntiwindupStrategy::NONE)
Initialize the PID controller and set the parameters.
- Deprecated:
{only when
antiwindup_strat == AntiwindupStrategy::NONE:} Old anti-windup technique is deprecated and will be removed by the ROS 2 Kilted Kaiju release.
Note
New gains are not applied if i_min > i_max or if u_min_ > u_max_.
Warning
{If you pass
AntiwindupStrategy::NONE, at runtime a warning will be printed:}"Old anti-windup technique is deprecated. This option will be removed by
the ROS 2 Kilted Kaiju release."
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – The max integral windup.
i_min – The min integral windup.
u_max – Upper output clamp.
u_min – Lower output clamp.
trk_tc – 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.
saturation – Enables output saturation. When true, the controller output is clamped between u_max and u_min.
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.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior. When a strategy other than ‘none’ is selected, it will override the controller’s default anti-windup behavior.
-
void set_gains(double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation, AntiwindupStrategy antiwindup_strat)
Set PID gains for the controller (preferred).
Note
New gains are not applied if u_min_ > u_max_.
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
u_max – Upper output clamp.
u_min – Lower output clamp.
trk_tc – 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.
saturation – Enables output saturation. When true, the controller output is clamped between u_max and u_min.
antiwindup_strat – Specifies the anti-windup strategy. Options: ‘back_calculation’, ‘conditional_integration’, or ‘none’. Note that the ‘back_calculation’ strategy use the tracking_time_constant parameter to tune the anti-windup behavior.
-
void setGains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false)
Set PID gains for the controller.
Note
New gains are not applied if i_min > i_max
- Parameters:
p – The proportional gain.
i – The integral gain.
d – The derivative gain.
i_max – Upper integral clamp.
i_min – Lower integral clamp.
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.
-
void set_gains(const Pid::Gains &gains)
Set PID gains for the controller.
Note
New gains are not applied if gains.i_min_ > gains.i_max_
- Parameters:
gains – A struct of the PID gain values
-
void setGains(const Pid::Gains &gains)
Set PID gains for the controller.
Note
New gains are not applied if gains.i_min_ > gains.i_max_
- Parameters:
gains – A struct of the PID gain values
-
void set_current_cmd(double cmd)
Set current command for this PID controller.
- Parameters:
cmd – command to set
-
void setCurrentCmd(double cmd)
Set current command for this PID controller.
- Parameters:
cmd – command to set
-
double get_current_cmd()
Return current command for this PID controller.
- Returns:
current cmd
-
double getCurrentCmd()
Return current command for this PID controller.
- Returns:
current cmd
-
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> get_pid_state_publisher()
Return PID state publisher.
- Returns:
shared_ptr to the PID state publisher
-
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> getPidStatePublisher()
Return PID state publisher.
- Returns:
shared_ptr to the PID state publisher
-
void get_current_pid_errors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
- Parameters:
pe[out] – The proportional error.
ie[out] – The weighted integral error.
de[out] – The derivative error.
-
void getCurrentPIDErrors(double &pe, double &ie, double &de)
Return PID error terms for the controller.
- Parameters:
pe[out] – The proportional error.
ie[out] – The integral error.
de[out] – The derivative error.
-
void print_values()
Print to console the current parameters.
-
void printValues()
Print to console the current parameters.
-
inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr get_parameters_callback_handle()
Return PID parameters callback handle.
- Returns:
shared_ptr to the PID parameters callback handle
-
inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr getParametersCallbackHandle()
Return PID parameters callback handle.
- Returns:
shared_ptr to the PID parameters callback handle