Go to the documentation of this file.
32 float dy = (float)(_odom.
y - target.
y);
33 float dx = (float)(_odom.
x - target.
x);
45 ROS_INFO(
"Multi Robot Controller: goal reached");
46 robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_DONE;
82 float theta = atan2(_odom.
y - target.
y, _odom.
x - target.
x);
85 float d_theta_comp = M_PI / 2 + d_theta;
86 float distance_to_goal = sqrt((_odom.
x - target.
x) * (_odom.
x - target.
x) +
87 (_odom.
y - target.
y) * (_odom.
y - target.
y));
88 float turn_radius_to_goal =
absolute(distance_to_goal / 2 / cos(d_theta_comp));
107 else if (turn_radius_to_goal <
108 10 * distance_to_goal)
110 float v_h = turn_radius_to_goal *
absolute(
w_);
135 while (_angle > M_PI)
139 while (_angle < -M_PI)
std::vector< PathPoint > path_
float normalizeAngle(float _angle)
void setGoalRadius(float _r)
Set the Goal Radius.
void setState(state s)
Set the State (run stop step wait_step)
bool checkGoal(PathPoint _odom)
void update(PathPoint _odom, float _delta_t)
updates the controller with the current robot position
Controller()
Construct a new Controller object.
void getSpeed(float *_v, float *_w)
Returns the current speed values.
size_t getProgress()
return progress,
float absolute(float _val)
enum velocity_controller::state_t state
void setPID(float _Kp, float _Ki, float _Kd)
sets the control parameters
size_t idx_path_target_point_
struct velocity_controller::Point_t PathPoint
void setPath(std::shared_ptr< std::vector< PathPoint >> _path)
Set the path the contorler has to follow.
void setSpeedParams(float _max_v, float _max_w)
Set the Speed Params of the controller.
bool isActive()
return progress, passed waypoints on the given path