Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
velocity_controller::Controller Class Reference

#include <controller.h>

Inheritance diagram for velocity_controller::Controller:
Inheritance graph
[legend]

Public Member Functions

 Controller ()
 Construct a new Controller object. More...
 
void getSpeed (float *_v, float *_w)
 Returns the current speed values. More...
 
void setGoalRadius (float _r)
 Set the Goal Radius. More...
 
void setPath (std::shared_ptr< std::vector< PathPoint >> _path)
 Set the path the contorler has to follow. More...
 
void setPID (float _Kp, float _Ki, float _Kd)
 sets the control parameters More...
 
void setSpeedParams (float _max_v, float _max_w)
 Set the Speed Params of the controller. More...
 
void setState (state s)
 Set the State (run stop step wait_step) More...
 
void update (PathPoint _odom, float _delta_t)
 updates the controller with the current robot position More...
 

Protected Attributes

PathPoint current_pose_
 

Private Member Functions

float absolute (float _val)
 
bool checkGoal (PathPoint _odom)
 
float normalizeAngle (float _angle)
 

Private Attributes

state actual_cmd_ = run
 
float e_dot_ = 0
 
float e_last_ = 0
 
float goal_radius_ = 0.25
 
float Kd_ = 1
 
float Ki_ = 0.0
 
float Kp_ = 5
 
float max_v_
 
float max_w_
 
std::shared_ptr< std::vector< PathPoint > > path_
 
std::vector< PathPoint >::iterator path_iterator_
 
bool plan_active = false
 
float v_
 
float w_
 

Detailed Description

Definition at line 27 of file controller.h.

Constructor & Destructor Documentation

velocity_controller::Controller::Controller ( )

Construct a new Controller object.

Definition at line 8 of file controller.cpp.

Member Function Documentation

float velocity_controller::Controller::absolute ( float  _val)
private

Definition at line 113 of file controller.cpp.

bool velocity_controller::Controller::checkGoal ( PathPoint  _odom)
private

Definition at line 26 of file controller.cpp.

void velocity_controller::Controller::getSpeed ( float *  _v,
float *  _w 
)

Returns the current speed values.

Parameters
_vthe linear speed
_wthe rotational speed

Definition at line 140 of file controller.cpp.

float velocity_controller::Controller::normalizeAngle ( float  _angle)
private

Definition at line 121 of file controller.cpp.

void velocity_controller::Controller::setGoalRadius ( float  _r)

Set the Goal Radius.

Parameters
_rthe radius which is used to marke a goal as visited

Definition at line 21 of file controller.cpp.

void velocity_controller::Controller::setPath ( std::shared_ptr< std::vector< PathPoint >>  _path)

Set the path the contorler has to follow.

Parameters
_paththe path as std::vector of points

Definition at line 14 of file controller.cpp.

void velocity_controller::Controller::setPID ( float  _Kp,
float  _Ki,
float  _Kd 
)

sets the control parameters

Parameters
_Kpthe proportional part of the controller
_Kithe integration part of the controller
_Kdthe differential part

Definition at line 51 of file controller.cpp.

void velocity_controller::Controller::setSpeedParams ( float  _max_v,
float  _max_w 
)

Set the Speed Params of the controller.

Parameters
_max_vmaximal linear speed
_max_wmaximal rotational speed

Definition at line 134 of file controller.cpp.

void velocity_controller::Controller::setState ( state  s)

Set the State (run stop step wait_step)

Parameters
sthe state (run stop wait_step step)

Definition at line 58 of file controller.cpp.

void velocity_controller::Controller::update ( PathPoint  _odom,
float  _delta_t 
)

updates the controller with the current robot position

Parameters
_odomthe current robot position
_delta_tthe time differenz used for the pid controlelr

Definition at line 63 of file controller.cpp.

Member Data Documentation

state velocity_controller::Controller::actual_cmd_ = run
private

Definition at line 100 of file controller.h.

PathPoint velocity_controller::Controller::current_pose_
protected

Definition at line 103 of file controller.h.

float velocity_controller::Controller::e_dot_ = 0
private

Definition at line 94 of file controller.h.

float velocity_controller::Controller::e_last_ = 0
private

Definition at line 93 of file controller.h.

float velocity_controller::Controller::goal_radius_ = 0.25
private

Definition at line 98 of file controller.h.

float velocity_controller::Controller::Kd_ = 1
private

Definition at line 96 of file controller.h.

float velocity_controller::Controller::Ki_ = 0.0
private

Definition at line 97 of file controller.h.

float velocity_controller::Controller::Kp_ = 5
private

Definition at line 95 of file controller.h.

float velocity_controller::Controller::max_v_
private

Definition at line 89 of file controller.h.

float velocity_controller::Controller::max_w_
private

Definition at line 89 of file controller.h.

std::shared_ptr<std::vector<PathPoint> > velocity_controller::Controller::path_
private

Definition at line 88 of file controller.h.

std::vector<PathPoint>::iterator velocity_controller::Controller::path_iterator_
private

Definition at line 91 of file controller.h.

bool velocity_controller::Controller::plan_active = false
private

Definition at line 92 of file controller.h.

float velocity_controller::Controller::v_
private

Definition at line 90 of file controller.h.

float velocity_controller::Controller::w_
private

Definition at line 90 of file controller.h.


The documentation for this class was generated from the following files:


tuw_multi_robot_ctrl
Author(s): Benjamin Binder
autogenerated on Mon Jun 10 2019 15:42:29