ros2_control - rolling
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
control_toolbox::PidROS Class Reference

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.
 
 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)
 
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.
 
void initPid (double p, double i, double d, double i_max, double i_min, bool antiwindup)
 Initialize the PID controller and set the parameters.
 
void initialize_from_args (double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_iterm)
 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_iterm)
 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_iterm)
 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.
 
void set_gains (double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
 Set PID gains for the controller.
 
void setGains (double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
 Set PID gains for the controller.
 
void 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_
 

Constructor & Destructor Documentation

◆ PidROS()

template<class NodeT >
control_toolbox::PidROS::PidROS ( std::shared_ptr< NodeT >  node_ptr,
std::string  prefix = std::string(""),
bool  prefix_is_for_params = false 
)
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

Parameters
nodeROS node
prefixprefix to add to the pid parameters. Per default is prefix interpreted as prefix for topics.
prefix_is_for_paramsprovided 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.

Member Function Documentation

◆ compute_command() [1/2]

double control_toolbox::PidROS::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
errorError since last call (error = target - state)
dtChange in time since last call in seconds
Returns
PID command

◆ compute_command() [2/2]

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.

Parameters
errorError since last call (error = target - state)
error_dotd(Error)/dt since last call
dtChange in time since last call in seconds
Returns
PID command

◆ computeCommand() [1/2]

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.

Parameters
errorError since last call (error = target - state)
error_dotd(Error)/dt since last call
dtChange in time since last call in seconds
Returns
PID command

◆ computeCommand() [2/2]

double control_toolbox::PidROS::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
errorError since last call (error = target - state)
dtChange in time since last call in seconds
Returns
PID command

◆ get_current_cmd()

double control_toolbox::PidROS::get_current_cmd ( )

Return current command for this PID controller.

Returns
current cmd

◆ get_current_pid_errors()

void control_toolbox::PidROS::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 integral error.
de[out]The derivative error.

◆ get_gains()

Pid::Gains control_toolbox::PidROS::get_gains ( )

Get PID gains for the controller.

Returns
gains A struct of the PID gain values

◆ get_parameters_callback_handle()

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr control_toolbox::PidROS::get_parameters_callback_handle ( )
inline

Return PID parameters callback handle.

Returns
shared_ptr to the PID parameters callback handle

◆ get_pid_state_publisher()

std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > control_toolbox::PidROS::get_pid_state_publisher ( )

Return PID state publisher.

Returns
shared_ptr to the PID state publisher

◆ getCurrentCmd()

double control_toolbox::PidROS::getCurrentCmd ( )

Return current command for this PID controller.

Returns
current cmd

◆ getCurrentPIDErrors()

void control_toolbox::PidROS::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.

◆ getGains()

Pid::Gains control_toolbox::PidROS::getGains ( )

Get PID gains for the controller.

Returns
gains A struct of the PID gain values

◆ getParametersCallbackHandle()

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr control_toolbox::PidROS::getParametersCallbackHandle ( )
inline

Return PID parameters callback handle.

Returns
shared_ptr to the PID parameters callback handle

◆ getPidStatePublisher()

std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > control_toolbox::PidROS::getPidStatePublisher ( )

Return PID state publisher.

Returns
shared_ptr to the PID state publisher

◆ initialize_from_args() [1/2]

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

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup 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
New gains are not applied if i_min_ > i_max_

◆ initialize_from_args() [2/2]

void control_toolbox::PidROS::initialize_from_args ( double  p,
double  i,
double  d,
double  i_max,
double  i_min,
bool  antiwindup,
bool  save_iterm 
)

Initialize the PID controller and set the parameters.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_minThe min integral windup.
antiwindupantiwindup.
save_itermsave integrator output between resets.
Note
New gains are not applied if i_min_ > i_max_

◆ initialize_from_ros_parameters()

bool control_toolbox::PidROS::initialize_from_ros_parameters ( )

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

◆ initPid() [1/3]

bool control_toolbox::PidROS::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

◆ initPid() [2/3]

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.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup 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
New gains are not applied if i_min_ > i_max_

◆ initPid() [3/3]

void control_toolbox::PidROS::initPid ( double  p,
double  i,
double  d,
double  i_max,
double  i_min,
bool  antiwindup,
bool  save_iterm 
)

Initialize the PID controller and set the parameters.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxThe max integral windup.
i_minThe min integral windup.
antiwindupantiwindup.
save_itermsave integrator output between resets.
Note
New gains are not applied if i_min_ > i_max_

◆ reset() [1/2]

void control_toolbox::PidROS::reset ( )

Reset the state of this PID controller.

Note
save_iterm parameter is read from ROS parameters

◆ reset() [2/2]

void control_toolbox::PidROS::reset ( bool  save_iterm)

Reset the state of this PID controller.

Parameters
save_itermboolean indicating if integral term is retained on reset()

◆ set_current_cmd()

void control_toolbox::PidROS::set_current_cmd ( double  cmd)

Set current command for this PID controller.

Parameters
cmdcommand to set

◆ set_gains() [1/2]

void control_toolbox::PidROS::set_gains ( const Pid::Gains gains)

Set PID gains for the controller.

Parameters
gainsA struct of the PID gain values
Note
New gains are not applied if gains.i_min_ > gains.i_max_

◆ set_gains() [2/2]

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

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup 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
New gains are not applied if i_min > i_max

◆ setCurrentCmd()

void control_toolbox::PidROS::setCurrentCmd ( double  cmd)

Set current command for this PID controller.

Parameters
cmdcommand to set

◆ setGains() [1/2]

void control_toolbox::PidROS::setGains ( const Pid::Gains gains)

Set PID gains for the controller.

Parameters
gainsA struct of the PID gain values
Note
New gains are not applied if gains.i_min_ > gains.i_max_

◆ setGains() [2/2]

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.

Parameters
pThe proportional gain.
iThe integral gain.
dThe derivative gain.
i_maxUpper integral clamp.
i_minLower integral clamp.
antiwindupAntiwindup 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
New gains are not applied if i_min > i_max

The documentation for this class was generated from the following files: