Class PidROS

Class Documentation

class PidROS

Public Functions

template<class NodeT>
inline explicit PidROS(std::shared_ptr<NodeT> node_ptr, std::string prefix = std::string(""), bool prefix_is_for_params = false)

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 true then “/” in the middle of the string will not be replaced with “.” for parameters prefix. “/” or “~/” at the beginning will be removed.

template<class NodeT>
inline explicit PidROS(std::shared_ptr<NodeT> node_ptr, const std::string &param_prefix)
template<class NodeT>
inline explicit PidROS(std::shared_ptr<NodeT> node_ptr, const std::string &param_prefix, const std::string &topic_prefix)

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 – 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.

template<class NodeT>
inline explicit PidROS(std::shared_ptr<NodeT> node_ptr, std::string param_prefix, std::string topic_prefix, bool activate_state_publisher)

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 – 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.

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 &param_prefix, const std::string &topic_prefix, bool activate_state_publisher)

Constructor of PidROS class with node_interfaces.

Parameters:
  • 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.

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.

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.

Returns:

True if all parameters are successfully set, False otherwise.

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.

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.

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.

Returns:

True if all parameters are successfully set, False otherwise.

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.

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.

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.

  • 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.

Returns:

True if all parameters are successfully set, False otherwise.

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), False otherwise

Returns:

False if the parameters are not set or if the parameters are invalid

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.

Note

This method is not RT safe

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

bool 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

Note

This method is not RT safe

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.

Returns:

True if all parameters are successfully set, False otherwise.

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).

Note

New gains are not applied if u_min_ > u_max_.

Note

This method is not RT safe

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.

Returns:

True if all parameters are successfully set, False otherwise.

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.

bool 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_

Note

This method is not RT safe

Parameters:

gains – A struct of the PID gain values

Returns:

True if all parameters are successfully set, False otherwise.

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

Protected Attributes

std::string topic_prefix_
std::string param_prefix_