Namespaces | |
| pidcontroller | |
Classes | |
| class | pidcontroller::PIDController |
Functions | |
| Eigen::Vector3d | pidcontroller::PIDController::compute_linvel_effort (Eigen::Vector3d goal, Eigen::Vector3d current, ros::Time last_time) |
| Computes the linear velocity effort to apply to each axis. More... | |
| double | pidcontroller::PIDController::compute_yawrate_effort (double goal, double current, ros::Time last_time) |
| Computes the yaw rate effort to apply. More... | |
| pidcontroller::PIDController::PIDController () | |
| void | pidcontroller::PIDController::setup_linvel_pid (double p_gain, double i_gain, double d_gain, double i_max, double i_min, const ros::NodeHandle &node) |
| Sets up the PID values for computation of the linear velocities effort. More... | |
| void | pidcontroller::PIDController::setup_yawrate_pid (double p_gain, double i_gain, double d_gain, double i_max, double i_min, const ros::NodeHandle &node) |
| Sets up the PID values for computation of the yaw rate effort. More... | |
| pidcontroller::PIDController::~PIDController () | |
| Eigen::Vector3d PIDController::compute_linvel_effort | ( | Eigen::Vector3d | goal, |
| Eigen::Vector3d | current, | ||
| ros::Time | last_time | ||
| ) |
Computes the linear velocity effort to apply to each axis.
Definition at line 55 of file pid_controller.cpp.
| double PIDController::compute_yawrate_effort | ( | double | goal, |
| double | current, | ||
| ros::Time | last_time | ||
| ) |
Computes the yaw rate effort to apply.
Definition at line 63 of file pid_controller.cpp.
| PIDController::PIDController | ( | ) |
Definition at line 18 of file pid_controller.cpp.
| void PIDController::setup_linvel_pid | ( | double | p_gain, |
| double | i_gain, | ||
| double | d_gain, | ||
| double | i_max, | ||
| double | i_min, | ||
| const ros::NodeHandle & | node | ||
| ) |
Sets up the PID values for computation of the linear velocities effort.
Definition at line 21 of file pid_controller.cpp.
| void PIDController::setup_yawrate_pid | ( | double | p_gain, |
| double | i_gain, | ||
| double | d_gain, | ||
| double | i_max, | ||
| double | i_min, | ||
| const ros::NodeHandle & | node | ||
| ) |
Sets up the PID values for computation of the yaw rate effort.
Definition at line 40 of file pid_controller.cpp.
|
inline |
Definition at line 28 of file pid_controller.h.
|
private |
Definition at line 54 of file pid_controller.h.
|
private |
Definition at line 55 of file pid_controller.h.
|
private |
Definition at line 56 of file pid_controller.h.
|
private |
Definition at line 57 of file pid_controller.h.