#include <segment_controller.h>
Definition at line 35 of file segment_controller.h.
| velocity_controller::SegmentController::SegmentController |
( |
| ) |
|
| float velocity_controller::SegmentController::absolute |
( |
float |
_val | ) |
|
|
private |
| bool velocity_controller::SegmentController::checkGoal |
( |
PathPoint |
_odom | ) |
|
|
private |
| bool velocity_controller::SegmentController::checkPrecondition |
( |
PathPoint |
p | ) |
|
|
private |
| 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 |
| 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 185 of file segment_controller.cpp.
| float velocity_controller::SegmentController::normalizeAngle |
( |
float |
_angle | ) |
|
|
private |
| 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 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
-
| _path | the 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
-
| _Kp | the proportional part of the controller |
| _Ki | the integration part of the controller |
| _Kd | the 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_v | maximal linear speed |
| _max_w | maximal 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
-
| s | the 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
-
| _odom | the current robot position |
| _delta_t | the 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
-
| pc | the robot id and step to sync |
Definition at line 33 of file segment_controller.cpp.
| state velocity_controller::SegmentController::actual_cmd_ = run |
|
private |
| std::vector<int> velocity_controller::SegmentController::actualPreconditions |
|
private |
| float velocity_controller::SegmentController::e_dot_ = 0 |
|
private |
| float velocity_controller::SegmentController::e_last_ = 0 |
|
private |
| float velocity_controller::SegmentController::goal_radius_ = 0.25 |
|
private |
| float velocity_controller::SegmentController::Kd_ = 1 |
|
private |
| float velocity_controller::SegmentController::Ki_ = 0.0 |
|
private |
| float velocity_controller::SegmentController::Kp_ = 5 |
|
private |
| float velocity_controller::SegmentController::max_v_ |
|
private |
| float velocity_controller::SegmentController::max_w_ |
|
private |
| std::shared_ptr<std::vector<PathPoint> > velocity_controller::SegmentController::path_ |
|
private |
| int velocity_controller::SegmentController::pathCounter_ = 0 |
|
private |
| bool velocity_controller::SegmentController::plan_active = false |
|
private |
| float velocity_controller::SegmentController::v_ |
|
private |
| float velocity_controller::SegmentController::w_ |
|
private |
The documentation for this class was generated from the following files: