![]() |
ros2_control - jazzy
|
Public Member Functions | |
template<class NodeT > | |
PidROS (std::shared_ptr< NodeT > node_ptr, std::string prefix=std::string(""), bool prefix_is_for_params=false) | |
Constructor of PidROS class. | |
template<class NodeT > | |
PidROS (std::shared_ptr< NodeT > node_ptr, const std::string ¶m_prefix) | |
template<class NodeT > | |
PidROS (std::shared_ptr< NodeT > node_ptr, const std::string ¶m_prefix, const std::string &topic_prefix) | |
Constructor of PidROS class. | |
template<class NodeT > | |
PidROS (std::shared_ptr< NodeT > node_ptr, std::string param_prefix, std::string topic_prefix, bool activate_state_publisher) | |
Constructor of PidROS class. | |
PidROS (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, std::string prefix=std::string(""), bool prefix_is_for_params=false) | |
PidROS (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, const std::string ¶m_prefix, const std::string &topic_prefix, bool activate_state_publisher) | |
Constructor of PidROS class with node_interfaces. | |
bool | 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. | |
void | initPid (double p, double i, double d, double i_max, double i_min, bool antiwindup) |
Initialize the PID controller and set the parameters. | |
bool | 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. | |
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. | |
bool | initialize_from_args (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat, bool save_i_term) |
Initialize the PID controller and set the parameters. | |
bool | initialize_from_ros_parameters () |
Initialize the PID controller based on already set parameters. | |
bool | initPid () |
Initialize the PID controller based on already set parameters. | |
void | reset () |
Reset the state of this PID controller. | |
void | reset (bool save_i_term) |
Reset the state of this PID controller. | |
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 . | |
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 . | |
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. | |
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. | |
Pid::Gains | get_gains () |
Get PID gains for the controller. | |
Pid::Gains | getGains () |
Get PID gains for the controller. | |
bool | set_gains (double p, double i, double d, double i_max, double i_min, bool antiwindup=false) |
Set PID gains for the controller. | |
bool | set_gains (double p, double i, double d, double u_max, double u_min, const AntiWindupStrategy &antiwindup_strat) |
Set PID gains for the controller (preferred). | |
void | setGains (double p, double i, double d, double i_max, double i_min, bool antiwindup=false) |
Set PID gains for the controller. | |
bool | set_gains (const Pid::Gains &gains) |
Set PID gains for the controller. | |
void | setGains (const Pid::Gains &gains) |
Set PID gains for the controller. | |
void | set_current_cmd (double cmd) |
Set current command for this PID controller. | |
void | setCurrentCmd (double cmd) |
Set current command for this PID controller. | |
double | get_current_cmd () |
Return current command for this PID controller. | |
double | getCurrentCmd () |
Return current command for this PID controller. | |
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > | get_pid_state_publisher () |
Return PID state publisher. | |
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > | getPidStatePublisher () |
Return PID state publisher. | |
void | get_current_pid_errors (double &pe, double &ie, double &de) |
Return PID error terms for the controller. | |
void | getCurrentPIDErrors (double &pe, double &ie, double &de) |
Return PID error terms for the controller. | |
void | print_values () |
Print to console the current parameters. | |
void | printValues () |
Print to console the current parameters. | |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | get_parameters_callback_handle () |
Return PID parameters callback handle. | |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | getParametersCallbackHandle () |
Return PID parameters callback handle. | |
Protected Attributes | |
std::string | topic_prefix_ |
std::string | param_prefix_ |
|
inlineexplicit |
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
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 true then "/" in the middle of the string will not be replaced with "." for parameters prefix. "/" or "~/" at the beginning will be removed. |
|
inlineexplicit |
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
node | Any ROS node |
param_prefix | prefix to add to the pid parameters. |
topic_prefix | prefix to add to the state publisher. If it starts with ~/ , topic will be local under the namespace of the node. If it starts with / or an alphanumeric character, topic will be in global namespace. |
|
inlineexplicit |
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
node | Any ROS node |
param_prefix | prefix to add to the pid parameters. |
topic_prefix | prefix to add to the state publisher. If it starts with ~/ , topic will be local under the namespace of the node. If it starts with / or an alphanumeric character, topic will be in global namespace. |
activate_state_publisher | If true, the publisher will be enabled after initialization. |
control_toolbox::PidROS::PidROS | ( | rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | node_base, |
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr | node_logging, | ||
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr | node_params, | ||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr | topics_interface, | ||
const std::string & | param_prefix, | ||
const std::string & | topic_prefix, | ||
bool | activate_state_publisher | ||
) |
Constructor of PidROS class with node_interfaces.
node_base | Node base interface pointer. |
node_logging | Node logging interface pointer. |
node_params | Node parameters interface pointer. |
topics_interface | Node topics interface pointer. |
param_prefix | Prefix to add to the PID parameters. This string is not manipulated, i.e., probably should end with . . |
topic_prefix | Prefix to add to the state publisher. This string is not manipulated, i.e., probably should end with / . If it starts with ~/ , topic will be local under the namespace of the node. If it starts with / or an alphanumeric character, topic will be in global namespace. |
activate_state_publisher | If true, the publisher will be enabled after initialization. |
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
.
error | Error since last call (error = target - state) |
dt | Change in time since last call in seconds |
double control_toolbox::PidROS::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.
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 |
double control_toolbox::PidROS::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.
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 |
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
.
error | Error since last call (error = target - state) |
dt | Change in time since last call in seconds |
double control_toolbox::PidROS::get_current_cmd | ( | ) |
Return current command for this PID controller.
Return PID error terms for the controller.
pe[out] | The proportional error. |
ie[out] | The weighted integral error. |
de[out] | The derivative error. |
Pid::Gains control_toolbox::PidROS::get_gains | ( | ) |
Get PID gains for the controller.
|
inline |
Return PID parameters callback handle.
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > control_toolbox::PidROS::get_pid_state_publisher | ( | ) |
Return PID state publisher.
double control_toolbox::PidROS::getCurrentCmd | ( | ) |
Return current command for this PID controller.
Return PID error terms for the controller.
pe[out] | The proportional error. |
ie[out] | The integral error. |
de[out] | The derivative error. |
Pid::Gains control_toolbox::PidROS::getGains | ( | ) |
Get PID gains for the controller.
|
inline |
Return PID parameters callback handle.
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > control_toolbox::PidROS::getPidStatePublisher | ( | ) |
Return PID state publisher.
bool control_toolbox::PidROS::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.
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. |
bool control_toolbox::PidROS::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.
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. |
bool control_toolbox::PidROS::initialize_from_args | ( | double | p, |
double | i, | ||
double | d, | ||
double | u_max, | ||
double | u_min, | ||
const AntiWindupStrategy & | antiwindup_strat, | ||
bool | save_i_term | ||
) |
Initialize the PID controller and set the parameters.
p | The proportional gain. |
i | The integral gain. |
d | The derivative gain. |
u_max | Upper output clamp. |
u_min | Lower output clamp. |
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 control_toolbox::PidROS::initialize_from_ros_parameters | ( | ) |
Initialize the PID controller based on already set parameters.
bool control_toolbox::PidROS::initPid | ( | ) |
Initialize the PID controller based on already set parameters.
void control_toolbox::PidROS::initPid | ( | double | p, |
double | i, | ||
double | d, | ||
double | i_max, | ||
double | i_min, | ||
bool | antiwindup | ||
) |
Initialize the PID controller and set the 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 control_toolbox::PidROS::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.
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 control_toolbox::PidROS::reset | ( | ) |
Reset the state of this PID controller.
Reset the state of this PID controller.
save_i_term | boolean indicating if integral term is retained on reset() |
Set current command for this PID controller.
cmd | command to set |
bool control_toolbox::PidROS::set_gains | ( | const Pid::Gains & | gains | ) |
Set PID gains for the controller.
gains | A struct of the PID gain values |
bool control_toolbox::PidROS::set_gains | ( | double | p, |
double | i, | ||
double | d, | ||
double | i_max, | ||
double | i_min, | ||
bool | antiwindup = false |
||
) |
Set PID gains for the controller.
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. |
bool control_toolbox::PidROS::set_gains | ( | double | p, |
double | i, | ||
double | d, | ||
double | u_max, | ||
double | u_min, | ||
const AntiWindupStrategy & | antiwindup_strat | ||
) |
Set PID gains for the controller (preferred).
p | The proportional gain. |
i | The integral gain. |
d | The derivative gain. |
u_max | Upper output clamp. |
u_min | Lower output clamp. |
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. |
Set current command for this PID controller.
cmd | command to set |
void control_toolbox::PidROS::setGains | ( | const Pid::Gains & | gains | ) |
Set PID gains for the controller.
gains | A struct of the PID gain values |
void control_toolbox::PidROS::setGains | ( | double | p, |
double | i, | ||
double | d, | ||
double | i_max, | ||
double | i_min, | ||
bool | antiwindup = false |
||
) |
Set PID gains for the controller.
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. |