segment_controller.cpp
Go to the documentation of this file.
2 #include <ros/ros.h>
3 #include <memory>
4 #include <cmath>
5 
6 
7 namespace velocity_controller
8 {
10  {
11  actual_cmd_ = run;
12  goodId = tuw_multi_robot_msgs::RobotInfo::GOOD_EMPTY;
13  }
14 
15  void SegmentController::setPath( std::shared_ptr< std::vector< PathPoint > > _path )
16  {
17  actualPreconditions.clear();
18  path_ = _path;
19  pathCounter_ = 0;
20  plan_active = true;
21  robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_DRIVING;
22  }
23 
25  {
26  return pathCounter_ - 1;
27  }
28 
29 
31  {
32  goal_radius_ = r;
33  }
34 
36  {
37  if(actualPreconditions.size() <= pc.robot)
38  actualPreconditions.resize(pc.robot + 1, 0);
39 
41  }
42 
43 
45  {
46  for ( const auto & pc : p.precondition )
47  {
48  int count = 0;
49 
50  if ( actualPreconditions.size() > pc.robot )
51  {
52  count = actualPreconditions[pc.robot];
53  }
54  if(count <= pc.stepCondition) //??? <= TODO
55  {
56  return false;
57  }
58  }
59  return true;
60  }
61 
62 
64  {
66  {
67  float dy = ( float )( _odom.y - (*path_)[pathCounter_].y );
68  float dx = ( float )( _odom.x - (*path_)[pathCounter_].x );
69 
70  if ( sqrt( dx * dx + dy * dy ) < goal_radius_ )
71  {
72  if ( pathCounter_ < path_->size() )
73  {
74  //ROS_INFO( "++" );
75  pathCounter_++;
76 
77  if ( actual_cmd_ == step )
79 
80 
81  if ( pathCounter_ >= path_->size() )
82  {
83  ROS_INFO( "Multi Robot Controller: goal reached" );
84  robot_status = tuw_multi_robot_msgs::RobotInfo::STATUS_DONE;
85  plan_active = false;
86  }
87  }
88  }
89  }
90  }
91 
92 
93  void SegmentController::setPID( float _Kp, float _Ki, float _Kd )
94  {
95  Kp_ = _Kp;
96  Kd_ = _Kd;
97  Ki_ = _Ki;
98  }
99 
101  {
102  actual_cmd_ = s;
103  }
104 
105 
106  void SegmentController::update( PathPoint _odom, float _delta_t )
107  {
108  checkGoal( _odom );
109 
111  {
112  float theta = atan2( _odom.y - (*path_)[pathCounter_].y, _odom.x - (*path_)[pathCounter_].x );
113  float d_theta = normalizeAngle( _odom.theta - theta + M_PI );
114 
115  float d_theta_comp = M_PI / 2 + d_theta;
116  float distance_to_goal = sqrt( ( _odom.x - (*path_)[pathCounter_].x ) * ( _odom.x - (*path_)[pathCounter_].x ) + ( _odom.y - (*path_)[pathCounter_].y ) * ( _odom.y - (*path_)[pathCounter_].y ) );
117  float turn_radius_to_goal = absolute( distance_to_goal / 2 / cos( d_theta_comp ) );
118 
119 
120  float e = -d_theta;
121 
122  e_dot_ += e;
123 
124  w_ = Kp_ * e + Ki_ * e_dot_ * _delta_t + Kd_ * ( e - e_last_ ) / _delta_t;
125  e_last_ = e;
126 
127  if ( w_ > max_w_ )
128  w_ = max_w_;
129  else if ( w_ < -max_w_ )
130  w_ = -max_w_;
131 
132  v_ = max_v_;
133 
134  if ( absolute( d_theta ) > M_PI / 4 ) //If angle is bigger than 90deg the robot should turn on point
135  {
136  v_ = 0;
137  }
138  else if ( turn_radius_to_goal < 10 * distance_to_goal ) //If we have a small radius to goal we should turn with the right radius
139  {
140  float v_h = turn_radius_to_goal * absolute( w_ );
141 
142  if ( v_ > v_h )
143  v_ = v_h;
144  }
145 
146  //ROS_INFO("(%f %f)(%f %f)", odom.x, odom.y, path_iterator->x, path_iterator->y);
147  //ROS_INFO("d %f t %f r %f, v %f w %f", distance_to_goal, d_theta / M_PI * 180, turn_radius_to_goal, v_, w_);
148  }
149  else
150  {
151  v_ = 0;
152  w_ = 0;
153  }
154  }
155 
156  float SegmentController::absolute( float _val )
157  {
158  if ( _val < 0 )
159  _val = -_val;
160 
161  return _val;
162 
163  }
164 
165  float SegmentController::normalizeAngle( float _angle )
166  {
167 
168  while ( _angle > M_PI )
169  {
170  _angle -= 2 * M_PI;
171  }
172 
173  while ( _angle < -M_PI )
174  {
175  _angle += 2 * M_PI;
176  }
177 
178  return _angle;
179  }
180 
181 
182  void SegmentController::setSpeedParams( float _max_v, float _max_w )
183  {
184  max_v_ = _max_v;
185  max_w_ = _max_w;
186  }
187 
188  void SegmentController::getSpeed( float* _v, float* _w )
189  {
190  *_v = v_;
191  *_w = w_;
192  }
193 
195  {
196  return robot_status;
197  }
198 
200  {
201  this->orderId = orderId;
202  }
204  {
205  this->goodId = goodId;
206  }
207 
209  {
210  return goodId;
211  }
212  void SegmentController::setOrderStatus(int orderStatus)
213  {
214  this->orderStatus = orderStatus;
215  }
217  {
218  return this->orderStatus;
219  }
220 
221 }
velocity_controller::PathPrecondition_t::stepCondition
int stepCondition
Definition: segment_controller.h:17
velocity_controller::PathPrecondition_t::robot
int robot
Definition: segment_controller.h:16
velocity_controller::SegmentController::orderId
int orderId
Definition: segment_controller.h:133
velocity_controller::SegmentController::orderStatus
int orderStatus
Definition: segment_controller.h:134
velocity_controller::SegmentController::getGoodId
int getGoodId()
Definition: segment_controller.cpp:208
velocity_controller::SegmentController::absolute
float absolute(float _val)
Definition: segment_controller.cpp:156
velocity_controller::Point_t::x
float x
Definition: controller.h:15
velocity_controller::SegmentController::v_
float v_
Definition: segment_controller.h:121
velocity_controller::step
@ step
Definition: controller.h:26
velocity_controller::SegmentController::goodId
int goodId
Definition: segment_controller.h:132
velocity_controller::SegmentController::plan_active
bool plan_active
Definition: segment_controller.h:123
s
XmlRpcServer s
ros.h
velocity_controller::Point_t::y
float y
Definition: controller.h:16
velocity_controller::SegmentController::getOrderStatus
int getOrderStatus()
Definition: segment_controller.cpp:216
velocity_controller::Point_t::theta
float theta
Definition: controller.h:17
velocity_controller::SegmentController::setGoodId
void setGoodId(int)
Definition: segment_controller.cpp:203
velocity_controller::SegmentController::setPath
void setPath(std::shared_ptr< std::vector< PathPoint >> _path)
Set the path the contorler has to follow.
Definition: segment_controller.cpp:15
velocity_controller::SegmentController::pathCounter_
int pathCounter_
Definition: segment_controller.h:122
velocity_controller::SegmentController::max_w_
float max_w_
Definition: segment_controller.h:120
velocity_controller::SegmentController::goal_radius_
float goal_radius_
Definition: segment_controller.h:129
velocity_controller::SegmentController::actualPreconditions
std::vector< int > actualPreconditions
Definition: segment_controller.h:136
velocity_controller::SegmentController::max_v_
float max_v_
Definition: segment_controller.h:120
velocity_controller::SegmentController::e_last_
float e_last_
Definition: segment_controller.h:124
velocity_controller::SegmentController::setOrderStatus
void setOrderStatus(int)
Definition: segment_controller.cpp:212
velocity_controller::stop
@ stop
Definition: controller.h:25
velocity_controller
Definition: controller.h:11
velocity_controller::run
@ run
Definition: controller.h:24
velocity_controller::SegmentController::getSpeed
void getSpeed(float *_v, float *_w)
Returns the current speed values.
Definition: segment_controller.cpp:188
velocity_controller::SegmentController::getCount
int getCount()
Returns the checkpoint number the robot is in.
Definition: segment_controller.cpp:24
segment_controller.h
velocity_controller::SegmentController::setSpeedParams
void setSpeedParams(float _max_v, float _max_w)
Set the Speed Params of the controller.
Definition: segment_controller.cpp:182
velocity_controller::SegmentController::getStatus
int getStatus()
Definition: segment_controller.cpp:194
velocity_controller::SegmentController::setState
void setState(state s)
Set the State (run stop step wait_step)
Definition: segment_controller.cpp:100
velocity_controller::SegmentController::setPID
void setPID(float _Kp, float _Ki, float _Kd)
sets the control parameters
Definition: segment_controller.cpp:93
velocity_controller::SegmentController::actual_cmd_
state actual_cmd_
Definition: segment_controller.h:138
velocity_controller::state
enum velocity_controller::state_t state
velocity_controller::SegmentController::path_
std::shared_ptr< std::vector< PathPoint > > path_
Definition: segment_controller.h:119
velocity_controller::PathPrecondition_t
Definition: segment_controller.h:14
velocity_controller::SegmentController::update
void update(PathPoint _odom, float _delta_t)
updates the controller with the current robot position
Definition: segment_controller.cpp:106
velocity_controller::SegmentController::setOrderId
void setOrderId(int)
Definition: segment_controller.cpp:199
velocity_controller::wait_step
@ wait_step
Definition: controller.h:27
velocity_controller::Point_t
Definition: controller.h:13
velocity_controller::SegmentController::setGoalRadius
void setGoalRadius(float _r)
Set the Goal Radius.
Definition: segment_controller.cpp:30
velocity_controller::SegmentController::Kp_
float Kp_
Definition: segment_controller.h:126
velocity_controller::SegmentController::SegmentController
SegmentController()
Construct a new Segment Controller object.
Definition: segment_controller.cpp:9
velocity_controller::SegmentController::checkGoal
bool checkGoal(PathPoint _odom)
Definition: segment_controller.cpp:63
velocity_controller::SegmentController::checkPrecondition
bool checkPrecondition(PathPoint p)
Definition: segment_controller.cpp:44
velocity_controller::SegmentController::Ki_
float Ki_
Definition: segment_controller.h:128
velocity_controller::SegmentController::e_dot_
float e_dot_
Definition: segment_controller.h:125
velocity_controller::SegmentController::Kd_
float Kd_
Definition: segment_controller.h:127
velocity_controller::SegmentController::updatePrecondition
void updatePrecondition(PathPrecondition pc)
updates the sync step of other robots
Definition: segment_controller.cpp:35
ROS_INFO
#define ROS_INFO(...)
velocity_controller::SegmentController::normalizeAngle
float normalizeAngle(float _angle)
Definition: segment_controller.cpp:165
velocity_controller::SegmentController::robot_status
int robot_status
Definition: segment_controller.h:131
velocity_controller::SegmentController::w_
float w_
Definition: segment_controller.h:121


tuw_multi_robot_ctrl
Author(s): Benjamin Binder
autogenerated on Wed Mar 2 2022 01:09:58