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
true
then “/” in the middle of the string will not be replaced with “.” for parameters prefix. “/” or “~/” at the beginning will be removed.
-
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 – The max integral windup.
i_min – The min integral windup.
antiwindup – antiwindup.
-
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.
-
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 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 getGains()
Get PID gains for the controller.
- Returns:
gains A struct of the PID gain values
-
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 – The max integral windup.
i_min – The min integral windup.
antiwindup – antiwindup.
-
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 setCurrentCmd(double cmd)
Set current command for this PID controller.
- Parameters:
cmd – command to set
-
double getCurrentCmd()
Return current command for this PID controller.
- Returns:
current cmd
-
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> getPidStatePublisher()
Return PID state publisher.
- Returns:
shared_ptr to the PID state publisher
-
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 printValues()
Print to console the current parameters.
-
inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr getParametersCallbackHandle()
Return PID parameters callback handle.
- Returns:
shared_ptr to the PID parameters callback handle