#include <controller.h>
Definition at line 30 of file controller.h.
◆ Controller()
velocity_controller::Controller::Controller |
( |
| ) |
|
◆ absolute()
float velocity_controller::Controller::absolute |
( |
float |
_val | ) |
|
|
private |
◆ checkGoal()
bool velocity_controller::Controller::checkGoal |
( |
PathPoint |
_odom | ) |
|
|
private |
◆ getGoodId()
int velocity_controller::Controller::getGoodId |
( |
| ) |
|
◆ getOrderId()
int velocity_controller::Controller::getOrderId |
( |
| ) |
|
◆ getOrderStatus()
int velocity_controller::Controller::getOrderStatus |
( |
| ) |
|
◆ 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
-
_v | the linear speed |
_w | the rotational speed |
Definition at line 152 of file controller.cpp.
◆ getStatus()
int velocity_controller::Controller::getStatus |
( |
| ) |
|
◆ 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 |
◆ setGoalRadius()
void velocity_controller::Controller::setGoalRadius |
( |
float |
_r | ) |
|
Set the Goal Radius.
- Parameters
-
_r | the 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 | ) |
|
◆ setOrderId()
void velocity_controller::Controller::setOrderId |
( |
int |
orderId | ) |
|
◆ setOrderStatus()
void velocity_controller::Controller::setOrderStatus |
( |
int |
orderStatus | ) |
|
◆ setPath()
void velocity_controller::Controller::setPath |
( |
std::shared_ptr< std::vector< PathPoint >> |
_path | ) |
|
Set the path the contorler has to follow.
- Parameters
-
_path | the 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
-
_Kp | the proportional part of the controller |
_Ki | the integration part of the controller |
_Kd | the 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_v | maximal linear speed |
_max_w | maximal 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
-
s | the 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
-
_odom | the current robot position |
_delta_t | the time differenz used for the pid controlelr |
Definition at line 74 of file controller.cpp.
◆ actual_cmd_
state velocity_controller::Controller::actual_cmd_ = run |
|
private |
◆ current_pose_
PathPoint velocity_controller::Controller::current_pose_ |
|
protected |
◆ e_dot_
float velocity_controller::Controller::e_dot_ = 0 |
|
private |
◆ e_last_
float velocity_controller::Controller::e_last_ = 0 |
|
private |
◆ goal_radius_
float velocity_controller::Controller::goal_radius_ = 0.25 |
|
private |
◆ goodId
int velocity_controller::Controller::goodId |
|
private |
◆ idx_path_target_point_
size_t velocity_controller::Controller::idx_path_target_point_ |
|
private |
◆ Kd_
float velocity_controller::Controller::Kd_ = 1 |
|
private |
◆ Ki_
float velocity_controller::Controller::Ki_ = 0.0 |
|
private |
◆ Kp_
float velocity_controller::Controller::Kp_ = 5 |
|
private |
◆ max_v_
float velocity_controller::Controller::max_v_ |
|
private |
◆ max_w_
float velocity_controller::Controller::max_w_ |
|
private |
◆ orderId
int velocity_controller::Controller::orderId |
|
private |
◆ orderStatus
int velocity_controller::Controller::orderStatus |
|
private |
◆ path_
std::vector<PathPoint> velocity_controller::Controller::path_ |
|
private |
◆ plan_active
bool velocity_controller::Controller::plan_active = false |
|
private |
◆ robot_status
int velocity_controller::Controller::robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_STOPPED |
|
private |
◆ v_
float velocity_controller::Controller::v_ |
|
private |
◆ w_
float velocity_controller::Controller::w_ |
|
private |
The documentation for this class was generated from the following files: