ros2_control - rolling
|
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. More... | |
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 | initPid (double p, double i, double d, double i_max, double i_min, bool antiwindup) |
Initialize the PID controller and set the parameters. More... | |
bool | initPid () |
Initialize the PID controller based on already set parameters. More... | |
void | reset () |
Reset the state of this PID controller. | |
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 . More... | |
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. More... | |
Pid::Gains | getGains () |
Get PID gains for the controller. More... | |
void | setGains (double p, double i, double d, double i_max, double i_min, bool antiwindup=false) |
Set PID gains for the controller. More... | |
void | setGains (const Pid::Gains &gains) |
Set PID gains for the controller. More... | |
void | setCurrentCmd (double cmd) |
Set current command for this PID controller. More... | |
double | getCurrentCmd () |
Return current command for this PID controller. More... | |
std::shared_ptr< rclcpp::Publisher< control_msgs::msg::PidState > > | getPidStatePublisher () |
Return PID state publisher. More... | |
void | getCurrentPIDErrors (double &pe, double &ie, double &de) |
Return PID error terms for the controller. More... | |
void | printValues () |
Print to console the current parameters. | |
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr | getParametersCallbackHandle () |
Return PID parameters callback handle. More... | |
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. |
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 |
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
.
error | Error since last call (error = target - state) |
dt | Change in time since last call in seconds |
double control_toolbox::PidROS::getCurrentCmd | ( | ) |
Return current command for this PID controller.
void control_toolbox::PidROS::getCurrentPIDErrors | ( | double & | pe, |
double & | ie, | ||
double & | de | ||
) |
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::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 | The max integral windup. |
i_min | The min integral windup. |
antiwindup | antiwindup. |
void control_toolbox::PidROS::setCurrentCmd | ( | double | cmd | ) |
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 | The max integral windup. |
i_min | The min integral windup. |
antiwindup | antiwindup. |