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

#include <segment_controller.h>

Public Member Functions

int getCount ()
 Returns the checkpoint number the robot is in. More...
 
bool getPlanActive ()
 
void getSpeed (float *_v, float *_w)
 Returns the current speed values. More...
 
 SegmentController ()
 Construct a new Segment Controller object. 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...
 
void updatePrecondition (PathPrecondition pc)
 updates the sync step of other robots More...
 

Private Member Functions

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

Private Attributes

state actual_cmd_ = run
 
std::vector< int > actualPreconditions
 
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_
 
int pathCounter_ = 0
 
bool plan_active = false
 
float v_
 
float w_
 

Detailed Description

Definition at line 35 of file segment_controller.h.

Constructor & Destructor Documentation

velocity_controller::SegmentController::SegmentController ( )

Construct a new Segment Controller object.

Definition at line 9 of file segment_controller.cpp.

Member Function Documentation

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

Definition at line 153 of file segment_controller.cpp.

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

Definition at line 61 of file segment_controller.cpp.

bool velocity_controller::SegmentController::checkPrecondition ( PathPoint  p)
private

Definition at line 42 of file segment_controller.cpp.

int velocity_controller::SegmentController::getCount ( )

Returns the checkpoint number the robot is in.

Returns
int returns the step of the checkpoint

Definition at line 22 of file segment_controller.cpp.

bool velocity_controller::SegmentController::getPlanActive ( )
inline

Definition at line 103 of file segment_controller.h.

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

Returns the current speed values.

Parameters
_vthe linear speed
_wthe rotational speed

Definition at line 185 of file segment_controller.cpp.

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

Definition at line 162 of file segment_controller.cpp.

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

Set the Goal Radius.

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

Definition at line 28 of file segment_controller.cpp.

void velocity_controller::SegmentController::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 segment_controller.cpp.

void velocity_controller::SegmentController::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 90 of file segment_controller.cpp.

void velocity_controller::SegmentController::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 179 of file segment_controller.cpp.

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

Set the State (run stop step wait_step)

Parameters
sthe state (run stop wait_step step)

Definition at line 97 of file segment_controller.cpp.

void velocity_controller::SegmentController::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 103 of file segment_controller.cpp.

void velocity_controller::SegmentController::updatePrecondition ( PathPrecondition  pc)

updates the sync step of other robots

Parameters
pcthe robot id and step to sync

Definition at line 33 of file segment_controller.cpp.

Member Data Documentation

state velocity_controller::SegmentController::actual_cmd_ = run
private

Definition at line 124 of file segment_controller.h.

std::vector<int> velocity_controller::SegmentController::actualPreconditions
private

Definition at line 122 of file segment_controller.h.

float velocity_controller::SegmentController::e_dot_ = 0
private

Definition at line 116 of file segment_controller.h.

float velocity_controller::SegmentController::e_last_ = 0
private

Definition at line 115 of file segment_controller.h.

float velocity_controller::SegmentController::goal_radius_ = 0.25
private

Definition at line 120 of file segment_controller.h.

float velocity_controller::SegmentController::Kd_ = 1
private

Definition at line 118 of file segment_controller.h.

float velocity_controller::SegmentController::Ki_ = 0.0
private

Definition at line 119 of file segment_controller.h.

float velocity_controller::SegmentController::Kp_ = 5
private

Definition at line 117 of file segment_controller.h.

float velocity_controller::SegmentController::max_v_
private

Definition at line 111 of file segment_controller.h.

float velocity_controller::SegmentController::max_w_
private

Definition at line 111 of file segment_controller.h.

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

Definition at line 110 of file segment_controller.h.

int velocity_controller::SegmentController::pathCounter_ = 0
private

Definition at line 113 of file segment_controller.h.

bool velocity_controller::SegmentController::plan_active = false
private

Definition at line 114 of file segment_controller.h.

float velocity_controller::SegmentController::v_
private

Definition at line 112 of file segment_controller.h.

float velocity_controller::SegmentController::w_
private

Definition at line 112 of file segment_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