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...
 
int getGoodId ()
 
int getOrderId ()
 
int getOrderStatus ()
 
size_t getProgress ()
 return progress, More...
 
void getSpeed (float *_v, float *_w)
 Returns the current speed values. More...
 
int getStatus ()
 
bool isActive ()
 return progress, passed waypoints on the given path More...
 
void setGoalRadius (float _r)
 Set the Goal Radius. More...
 
void setGoodId (int)
 
void setOrderId (int)
 
void setOrderStatus (int)
 
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
 
int goodId
 
size_t idx_path_target_point_
 
float Kd_ = 1
 
float Ki_ = 0.0
 
float Kp_ = 5
 
float max_v_
 
float max_w_
 
int orderId
 
int orderStatus
 
std::vector< PathPointpath_
 
bool plan_active = false
 
int robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_STOPPED
 
float v_
 
float w_
 

Detailed Description

Definition at line 30 of file controller.h.

Constructor & Destructor Documentation

◆ Controller()

velocity_controller::Controller::Controller ( )

Construct a new Controller object.

Definition at line 8 of file controller.cpp.

Member Function Documentation

◆ absolute()

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

Definition at line 125 of file controller.cpp.

◆ checkGoal()

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

Definition at line 27 of file controller.cpp.

◆ getGoodId()

int velocity_controller::Controller::getGoodId ( )

Definition at line 172 of file controller.cpp.

◆ getOrderId()

int velocity_controller::Controller::getOrderId ( )

◆ getOrderStatus()

int velocity_controller::Controller::getOrderStatus ( )

Definition at line 180 of file controller.cpp.

◆ getProgress()

size_t velocity_controller::Controller::getProgress ( )

return progress,

Returns
passed waypoints on the given path

Definition at line 61 of file controller.cpp.

◆ getSpeed()

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

Returns the current speed values.

Parameters
_vthe linear speed
_wthe rotational speed

Definition at line 152 of file controller.cpp.

◆ getStatus()

int velocity_controller::Controller::getStatus ( )

Definition at line 158 of file controller.cpp.

◆ isActive()

bool velocity_controller::Controller::isActive ( )

return progress, passed waypoints on the given path

Returns
if the vehicle is driving

Definition at line 65 of file controller.cpp.

◆ normalizeAngle()

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

Definition at line 133 of file controller.cpp.

◆ setGoalRadius()

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 22 of file controller.cpp.

◆ setGoodId()

void velocity_controller::Controller::setGoodId ( int  goodId)

Definition at line 167 of file controller.cpp.

◆ setOrderId()

void velocity_controller::Controller::setOrderId ( int  orderId)

Definition at line 163 of file controller.cpp.

◆ setOrderStatus()

void velocity_controller::Controller::setOrderStatus ( int  orderStatus)

Definition at line 176 of file controller.cpp.

◆ setPath()

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 15 of file controller.cpp.

◆ setPID()

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 54 of file controller.cpp.

◆ setSpeedParams()

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 146 of file controller.cpp.

◆ setState()

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 69 of file controller.cpp.

◆ update()

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 74 of file controller.cpp.

Member Data Documentation

◆ actual_cmd_

state velocity_controller::Controller::actual_cmd_ = run
private

Definition at line 127 of file controller.h.

◆ current_pose_

PathPoint velocity_controller::Controller::current_pose_
protected

Definition at line 130 of file controller.h.

◆ e_dot_

float velocity_controller::Controller::e_dot_ = 0
private

Definition at line 115 of file controller.h.

◆ e_last_

float velocity_controller::Controller::e_last_ = 0
private

Definition at line 114 of file controller.h.

◆ goal_radius_

float velocity_controller::Controller::goal_radius_ = 0.25
private

Definition at line 125 of file controller.h.

◆ goodId

int velocity_controller::Controller::goodId
private

Definition at line 121 of file controller.h.

◆ idx_path_target_point_

size_t velocity_controller::Controller::idx_path_target_point_
private

Definition at line 110 of file controller.h.

◆ Kd_

float velocity_controller::Controller::Kd_ = 1
private

Definition at line 117 of file controller.h.

◆ Ki_

float velocity_controller::Controller::Ki_ = 0.0
private

Definition at line 118 of file controller.h.

◆ Kp_

float velocity_controller::Controller::Kp_ = 5
private

Definition at line 116 of file controller.h.

◆ max_v_

float velocity_controller::Controller::max_v_
private

Definition at line 111 of file controller.h.

◆ max_w_

float velocity_controller::Controller::max_w_
private

Definition at line 111 of file controller.h.

◆ orderId

int velocity_controller::Controller::orderId
private

Definition at line 122 of file controller.h.

◆ orderStatus

int velocity_controller::Controller::orderStatus
private

Definition at line 123 of file controller.h.

◆ path_

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

Definition at line 109 of file controller.h.

◆ plan_active

bool velocity_controller::Controller::plan_active = false
private

Definition at line 113 of file controller.h.

◆ robot_status

int velocity_controller::Controller::robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_STOPPED
private

Definition at line 120 of file controller.h.

◆ v_

float velocity_controller::Controller::v_
private

Definition at line 112 of file controller.h.

◆ w_

float velocity_controller::Controller::w_
private

Definition at line 112 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 Feb 28 2022 23:57:38