#include <pid.h>
|
bool | init (const ros::NodeHandle &nh) |
| initialize gain settings from ROS parameter values More...
|
|
| PID (double p, double i, double d, double i_max, double i_min) |
| Constructor. More...
|
|
| PID () |
| Constructor. Starts all gains and limits at zero. More...
|
|
void | reset () |
| Reset integral wind-up term. More...
|
|
double | update (double error, double dt) |
| Run PID calculation and return control result. More...
|
|
double | update (double error, double error_dot, double dt) |
| Run PID calculation and return control result. More...
|
|
Definition at line 45 of file pid.h.
◆ PID() [1/2]
robot_controllers::PID::PID |
( |
double |
p, |
|
|
double |
i, |
|
|
double |
d, |
|
|
double |
i_max, |
|
|
double |
i_min |
|
) |
| |
Constructor.
- Parameters
-
p | proportional gain |
i | integral gain |
d | derivative gain |
i_max | integral wind-up max value |
i_min | integral wind-up min value |
Definition at line 47 of file pid.cpp.
◆ PID() [2/2]
robot_controllers::PID::PID |
( |
| ) |
|
Constructor. Starts all gains and limits at zero.
Definition at line 58 of file pid.cpp.
◆ checkGains()
bool robot_controllers::PID::checkGains |
( |
| ) |
|
|
protected |
Checks and fixes gain settings.
- Returns
- true is gains are ok, false if gains are invalid
Definition at line 92 of file pid.cpp.
◆ init()
initialize gain settings from ROS parameter values
Definition at line 68 of file pid.cpp.
◆ reset()
void robot_controllers::PID::reset |
( |
| ) |
|
Reset integral wind-up term.
Definition at line 140 of file pid.cpp.
◆ update() [1/2]
double robot_controllers::PID::update |
( |
double |
error, |
|
|
double |
dt |
|
) |
| |
Run PID calculation and return control result.
- Parameters
-
error | error term (goal-actual) |
dt | timestep used for calculating derivative term and integral windup |
- Returns
- calculated PID command
PID derivate term is calculated from change in error value and dt
Definition at line 146 of file pid.cpp.
◆ update() [2/2]
double robot_controllers::PID::update |
( |
double |
error, |
|
|
double |
error_dot, |
|
|
double |
dt |
|
) |
| |
Run PID calculation and return control result.
- Parameters
-
error | error term (goal-actual) |
error_dot | value that is used for derivative term calculation |
dt | timestep used for integral windup |
- Returns
- calculated PID command
Definition at line 164 of file pid.cpp.
◆ d_gain_
double robot_controllers::PID::d_gain_ |
|
protected |
derivative gain
Definition at line 99 of file pid.h.
◆ error_last_
double robot_controllers::PID::error_last_ |
|
protected |
Last error value, used for calculating error_dot when not provided.
Definition at line 107 of file pid.h.
◆ i_gain_
double robot_controllers::PID::i_gain_ |
|
protected |
integral gain
Definition at line 97 of file pid.h.
◆ i_max_
double robot_controllers::PID::i_max_ |
|
protected |
integral gain min and max limits
Definition at line 101 of file pid.h.
◆ i_min_
double robot_controllers::PID::i_min_ |
|
protected |
◆ i_term_
double robot_controllers::PID::i_term_ |
|
protected |
integral wind-up term
Definition at line 104 of file pid.h.
◆ p_gain_
double robot_controllers::PID::p_gain_ |
|
protected |
proportial gain
Definition at line 95 of file pid.h.
The documentation for this class was generated from the following files: