Classes | Namespaces | Functions | Variables
Test_utils

Classes

class  pidcontroller::PIDController

Namespaces

namespace  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.
double pidcontroller::PIDController::compute_yawrate_effort (double goal, double current, ros::Time last_time)
 Computes the yaw rate effort to apply.
 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.
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.
 pidcontroller::PIDController::~PIDController ()

Variables

control_toolbox::Pid pidcontroller::PIDController::pid_linvel_x
control_toolbox::Pid pidcontroller::PIDController::pid_linvel_y
control_toolbox::Pid pidcontroller::PIDController::pid_linvel_z
control_toolbox::Pid pidcontroller::PIDController::pid_yaw_rate

Function Documentation

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.

Definition at line 28 of file pid_controller.h.


Variable Documentation

Definition at line 54 of file pid_controller.h.

Definition at line 55 of file pid_controller.h.

Definition at line 56 of file pid_controller.h.

Definition at line 57 of file pid_controller.h.



test_mavros
Author(s): Nuno Marques , Vladimir Ermakov
autogenerated on Sat Jun 8 2019 19:55:31