#include <segment_controller.h>
Definition at line 36 of file segment_controller.h.
◆ SegmentController()
velocity_controller::SegmentController::SegmentController |
( |
| ) |
|
◆ absolute()
float velocity_controller::SegmentController::absolute |
( |
float |
_val | ) |
|
|
private |
◆ checkGoal()
bool velocity_controller::SegmentController::checkGoal |
( |
PathPoint |
_odom | ) |
|
|
private |
◆ checkPrecondition()
bool velocity_controller::SegmentController::checkPrecondition |
( |
PathPoint |
p | ) |
|
|
private |
◆ getCount()
int velocity_controller::SegmentController::getCount |
( |
| ) |
|
Returns the checkpoint number the robot is in.
- Returns
- int returns the step of the checkpoint
Definition at line 24 of file segment_controller.cpp.
◆ getGoodId()
int velocity_controller::SegmentController::getGoodId |
( |
| ) |
|
◆ getOrderId()
int velocity_controller::SegmentController::getOrderId |
( |
| ) |
|
◆ getOrderStatus()
int velocity_controller::SegmentController::getOrderStatus |
( |
| ) |
|
◆ getPlanActive()
bool velocity_controller::SegmentController::getPlanActive |
( |
| ) |
|
|
inline |
◆ getSpeed()
void velocity_controller::SegmentController::getSpeed |
( |
float * |
_v, |
|
|
float * |
_w |
|
) |
| |
Returns the current speed values.
- Parameters
-
_v | the linear speed |
_w | the rotational speed |
Definition at line 188 of file segment_controller.cpp.
◆ getStatus()
int velocity_controller::SegmentController::getStatus |
( |
| ) |
|
◆ normalizeAngle()
float velocity_controller::SegmentController::normalizeAngle |
( |
float |
_angle | ) |
|
|
private |
◆ setGoalRadius()
void velocity_controller::SegmentController::setGoalRadius |
( |
float |
_r | ) |
|
Set the Goal Radius.
- Parameters
-
_r | the radius which is used to marke a goal as visited |
Definition at line 30 of file segment_controller.cpp.
◆ setGoodId()
void velocity_controller::SegmentController::setGoodId |
( |
int |
goodId | ) |
|
◆ setOrderId()
void velocity_controller::SegmentController::setOrderId |
( |
int |
orderId | ) |
|
◆ setOrderStatus()
void velocity_controller::SegmentController::setOrderStatus |
( |
int |
orderStatus | ) |
|
◆ setPath()
void velocity_controller::SegmentController::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 segment_controller.cpp.
◆ setPID()
void velocity_controller::SegmentController::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 93 of file segment_controller.cpp.
◆ setSpeedParams()
void velocity_controller::SegmentController::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 182 of file segment_controller.cpp.
◆ setState()
void velocity_controller::SegmentController::setState |
( |
state |
s | ) |
|
Set the State (run stop step wait_step)
- Parameters
-
s | the state (run stop wait_step step) |
Definition at line 100 of file segment_controller.cpp.
◆ update()
void velocity_controller::SegmentController::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 106 of file segment_controller.cpp.
◆ updatePrecondition()
void velocity_controller::SegmentController::updatePrecondition |
( |
PathPrecondition |
pc | ) |
|
updates the sync step of other robots
- Parameters
-
pc | the robot id and step to sync |
Definition at line 35 of file segment_controller.cpp.
◆ actual_cmd_
state velocity_controller::SegmentController::actual_cmd_ = run |
|
private |
◆ actualPreconditions
std::vector<int> velocity_controller::SegmentController::actualPreconditions |
|
private |
◆ e_dot_
float velocity_controller::SegmentController::e_dot_ = 0 |
|
private |
◆ e_last_
float velocity_controller::SegmentController::e_last_ = 0 |
|
private |
◆ goal_radius_
float velocity_controller::SegmentController::goal_radius_ = 0.25 |
|
private |
◆ goodId
int velocity_controller::SegmentController::goodId |
|
private |
◆ Kd_
float velocity_controller::SegmentController::Kd_ = 1 |
|
private |
◆ Ki_
float velocity_controller::SegmentController::Ki_ = 0.0 |
|
private |
◆ Kp_
float velocity_controller::SegmentController::Kp_ = 5 |
|
private |
◆ max_v_
float velocity_controller::SegmentController::max_v_ |
|
private |
◆ max_w_
float velocity_controller::SegmentController::max_w_ |
|
private |
◆ orderId
int velocity_controller::SegmentController::orderId |
|
private |
◆ orderStatus
int velocity_controller::SegmentController::orderStatus |
|
private |
◆ path_
std::shared_ptr<std::vector<PathPoint> > velocity_controller::SegmentController::path_ |
|
private |
◆ pathCounter_
int velocity_controller::SegmentController::pathCounter_ = 0 |
|
private |
◆ plan_active
bool velocity_controller::SegmentController::plan_active = false |
|
private |
◆ robot_status
int velocity_controller::SegmentController::robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_STOPPED |
|
private |
◆ v_
float velocity_controller::SegmentController::v_ |
|
private |
◆ w_
float velocity_controller::SegmentController::w_ |
|
private |
The documentation for this class was generated from the following files: