ftc_planner.cpp
Go to the documentation of this file.
1 
18 #include <ros/ros.h>
19 
21 
23 
25 
26 namespace ftc_local_planner
27 {
28 
29  FTCPlanner::FTCPlanner()
30  {
31  }
32 
33  void FTCPlanner::initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros)
34  {
35  ros::NodeHandle private_nh("~/" + name);
36  local_plan_publisher_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
37  costmap_ros_ = costmap_ros;
38  tf_ = tf;
39  first_setPlan_ = true;
40  rotate_to_global_plan_ = false;
41  goal_reached_ = false;
42  stand_at_goal_ = false;
43  cmd_vel_angular_z_rotate_ = 0;
44  cmd_vel_linear_x_ = 0;
45  cmd_vel_angular_z_ = 0;
46 
47  //Parameter for dynamic reconfigure
48  dsrv_ = new dynamic_reconfigure::Server<FTCPlannerConfig>(private_nh);
49  dynamic_reconfigure::Server<FTCPlannerConfig>::CallbackType cb = boost::bind(&FTCPlanner::reconfigureCB, this, _1, _2);
50  dsrv_->setCallback(cb);
51 
52  joinCostmap_ = new JoinCostmap();
53 
54  ROS_INFO("FTCPlanner: Version 2 Init.");
55  }
56 
57  void FTCPlanner::reconfigureCB(FTCPlannerConfig &config, uint32_t level)
58  {
59  if (config.restore_defaults)
60  {
61  config = default_config_;
62  config.restore_defaults = false;
63  }
64  config_ = config;
65  }
66 
67  bool FTCPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& plan)
68  {
69  global_plan_ = plan;
70 
71  //First start of the local plan. First global plan.
72  bool first_use = false;
73  if(first_setPlan_)
74  {
75  if(config_.join_obstacle){
76  //init joincostmap with local an global costmap.
77  joinCostmap_->initialize(costmap_ros_, global_costmap_ros_);
78  }
79 
80  first_setPlan_ = false;
81  ftc_local_planner::getXPose(*tf_,global_plan_, costmap_ros_->getGlobalFrameID(),old_goal_pose_,global_plan_.size()-1);
82  first_use = true;
83  }
84 
85  ftc_local_planner::getXPose(*tf_,global_plan_, costmap_ros_->getGlobalFrameID(),goal_pose_,global_plan_.size()-1);
86  //Have the new global plan an new goal, reset. Else dont reset.
87  if(std::abs(std::abs(old_goal_pose_.getOrigin().getX())-std::abs(goal_pose_.getOrigin().getX())) <= config_.position_accuracy &&
88  std::abs(std::abs(old_goal_pose_.getOrigin().getY())-std::abs(goal_pose_.getOrigin().getY())) <= config_.position_accuracy && !first_use
89  && std::abs(angles::shortest_angular_distance(tf::getYaw(old_goal_pose_.getRotation()), tf::getYaw(goal_pose_.getRotation()))) <= config_.rotation_accuracy)
90  {
91  ROS_DEBUG("FTCPlanner: Old Goal == new Goal.");
92  }
93  else
94  {
95  //Rotate to first global plan point.
96  rotate_to_global_plan_ = true;
97  goal_reached_ = false;
98  stand_at_goal_ = false;
99  ROS_INFO("FTCPlanner: New Goal. Start new routine.");
100  }
101 
102  old_goal_pose_ = goal_pose_;
103 
104  return true;
105  }
106 
107  bool FTCPlanner::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
108  {
109 
110  ros::Time begin = ros::Time::now();
111 
112  tf::Stamped<tf::Pose> current_pose;
113  costmap_ros_->getRobotPose(current_pose);
114 
115  //Join the actual global an local costmap in the global costmap.
116  if(config_.join_obstacle){
117  joinCostmap_->joinMaps();
118  }
119  int max_point = 0;
120  //First part of the routine. Rotatio to the first global plan orientation.
121  if(rotate_to_global_plan_)
122  {
123  double angle_to_global_plan = calculateGlobalPlanAngle(current_pose, global_plan_, checkMaxDistance(current_pose));
124  rotate_to_global_plan_ = rotateToOrientation(angle_to_global_plan, cmd_vel, 0.1);
125  }
126  //Second part of the routine. Drive alonge the global plan.
127  else
128  {
129 
130  double distance = sqrt(pow((goal_pose_.getOrigin().getX()-current_pose.getOrigin().getX()),2)+pow((goal_pose_.getOrigin().getY()-current_pose.getOrigin().getY()),2));
131 
132  //Check if robot near enough to global goal.
133  if(distance > config_.position_accuracy && !stand_at_goal_)
134  {
135 
136  if(fabs(calculateGlobalPlanAngle(current_pose, global_plan_, checkMaxDistance(current_pose)) > 1.2))
137  {
138  ROS_INFO("FTCPlanner: Excessive deviation from global plan orientation. Start routine new.");
139  rotate_to_global_plan_ = true;
140  }
141 
142  max_point = driveToward(current_pose, cmd_vel);
143 
144  if(!checkCollision(max_point))
145  {
146  return false;
147  }
148  }
149  //Third part of the routine. Rotate at goal to goal orientation.
150  else
151  {
152  if(!stand_at_goal_)
153  {
154  ROS_INFO("FTCPlanner: Stand at goal. Rotate to goal orientation.");
155  }
156  stand_at_goal_ = true;
157 
158 
159  //Get the goal orientation.
160  double angle_to_global_plan = angles::shortest_angular_distance(tf::getYaw(current_pose.getRotation()), tf::getYaw(goal_pose_.getRotation()));
161  //Rotate until goalorientation is reached.
162  if(!rotateToOrientation(angle_to_global_plan, cmd_vel, config_.rotation_accuracy))
163  {
164  goal_reached_ = true;
165  }
166  cmd_vel.linear.x = 0;
167  cmd_vel.linear.y = 0;
168  }
169  }
170 
171  publishPlan(max_point);
172 
173  ros::Time end = ros::Time::now();
174  ros::Duration duration = end - begin;
175  ROS_DEBUG("FTCPlanner: Calculation time: %f seconds", duration.toSec());
176  return true;
177  }
178 
179  int FTCPlanner::checkMaxDistance(tf::Stamped<tf::Pose> current_pose)
180  {
181  int max_point = 0;
182  tf::Stamped<tf::Pose> x_pose;
183  transformed_global_plan_.clear();
184  for (unsigned int i = 0; i < global_plan_.size(); i++)
185  {
186  ftc_local_planner::getXPose(*tf_,global_plan_, costmap_ros_->getGlobalFrameID(),x_pose,i);
187  double distance = sqrt(pow((x_pose.getOrigin().getX()-current_pose.getOrigin().getX()),2)+pow((x_pose.getOrigin().getY()-current_pose.getOrigin().getY()),2));
188 
190  ros::Time::now(),
191  costmap_ros_->getGlobalFrameID());
192  geometry_msgs::PoseStamped pose;
193  tf::poseStampedTFToMsg(p, pose);
194  transformed_global_plan_.push_back(pose);
195 
196  max_point = i-1;
197  //If distance higher than maximal moveable distance in sim_time.
198  if(distance > (config_.max_x_vel*config_.sim_time))
199  {
200  break;
201  }
202  }
203  if(max_point < 0)
204  {
205  max_point = 0;
206  }
207  return max_point;
208  }
209 
210  int FTCPlanner::checkMaxAngle(int points, tf::Stamped<tf::Pose> current_pose)
211  {
212  int max_point = points;
213  double angle = 0;
214  for(int i = max_point; i >= 0; i--)
215  {
216  angle = calculateGlobalPlanAngle(current_pose, global_plan_, i);
217 
218  max_point = i;
219  //check if the angle is moveable
220  if(fabs(angle) < config_.max_rotation_vel*config_.sim_time)
221  {
222  break;
223  }
224  }
225  return max_point;
226  }
227 
228  double FTCPlanner::calculateGlobalPlanAngle(tf::Stamped<tf::Pose> current_pose, const std::vector<geometry_msgs::PoseStamped>& plan, int point)
229  {
230  if(point >= (int)plan.size())
231  {
232  point = plan.size()-1;
233  }
234  double angle = 0;
235  double current_th = tf::getYaw(current_pose.getRotation());
236  for(int i = 0; i <= point; i++)
237  {
238  geometry_msgs::PoseStamped x_pose;
239  x_pose=transformed_global_plan_.at(i);
240 
241  //Calculate the angles between robotpose and global plan point pose
242  double angle_to_goal = atan2(x_pose.pose.position.y - current_pose.getOrigin().getY(),
243  x_pose.pose.position.x - current_pose.getOrigin().getX());
244  angle += angle_to_goal;
245  }
246 
247  //average
248  angle = angle/(point+1);
249 
250  return angles::shortest_angular_distance(current_th, angle);
251  }
252 
253  bool FTCPlanner::rotateToOrientation(double angle, geometry_msgs::Twist& cmd_vel, double accuracy)
254  {
255 
256  if((cmd_vel_linear_x_ - 0.1) >= 0){
257  cmd_vel.linear.x = cmd_vel_linear_x_ - 0.1;
258  cmd_vel_linear_x_ = cmd_vel_linear_x_ - 0.1;
259  }
260  if(fabs(angle) > accuracy)
261  {
262  //Slow down
263  if(config_.max_rotation_vel >= fabs(angle) * (config_.acceleration_z+config_.slow_down_factor))
264  {
265  ROS_DEBUG("FTCPlanner: Slow down.");
266  if(angle < 0)
267  {
268  if(cmd_vel_angular_z_rotate_ >= -config_.min_rotation_vel)
269  {
270  cmd_vel_angular_z_rotate_ = - config_.min_rotation_vel;
271  cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
272 
273  }
274  else
275  {
276  cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ + config_.acceleration_z/config_.local_planner_frequence;
277  cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
278  }
279  }
280  if(angle > 0)
281  {
282  if(cmd_vel_angular_z_rotate_ <= config_.min_rotation_vel)
283  {
284  cmd_vel_angular_z_rotate_ = config_.min_rotation_vel;
285  cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
286 
287  }
288  else
289  {
290  cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ - config_.acceleration_z/config_.local_planner_frequence;
291  cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
292  }
293  }
294  }
295  else
296  {
297  //Speed up
298  if(fabs(cmd_vel_angular_z_rotate_) < config_.max_rotation_vel)
299  {
300  ROS_DEBUG("FTCPlanner: Speeding up");
301  if(angle < 0)
302  {
303  cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ - config_.acceleration_z/config_.local_planner_frequence;
304 
305  if(fabs(cmd_vel_angular_z_rotate_) > config_.max_rotation_vel)
306  {
307  cmd_vel_angular_z_rotate_ = - config_.max_rotation_vel;
308  }
309  cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
310  }
311  if(angle > 0)
312  {
313  cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ + config_.acceleration_z/config_.local_planner_frequence;
314 
315  if(fabs(cmd_vel_angular_z_rotate_) > config_.max_rotation_vel)
316  {
317  cmd_vel_angular_z_rotate_ = config_.max_rotation_vel;
318  }
319 
320  cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
321  }
322  }
323  else
324  {
325  cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
326  }
327  }
328  ROS_DEBUG("FTCPlanner: cmd_vel.z: %f, angle: %f", cmd_vel.angular.z, angle);
329  return true;
330  }
331  else
332  {
333  cmd_vel_angular_z_rotate_ = 0;
334  cmd_vel.angular.z = 0;
335  return false;
336  }
337  }
338 
339  int FTCPlanner::driveToward(tf::Stamped<tf::Pose> current_pose, geometry_msgs::Twist& cmd_vel)
340  {
341  double distance = 0;
342  double angle = 0;
343  int max_point = 0;
344 
345  //Search for max achievable point on global plan.
346  max_point = checkMaxDistance(current_pose);
347  max_point = checkMaxAngle(max_point, current_pose);
348 
349 
350  double cmd_vel_linear_x_old = cmd_vel_linear_x_;
351  double cmd_vel_angular_z_old = cmd_vel_angular_z_;
352 
353  geometry_msgs::PoseStamped x_pose;
354  x_pose = transformed_global_plan_.at(max_point);
355 
356  distance = sqrt(pow((x_pose.pose.position.x-current_pose.getOrigin().getX()),2)+pow((x_pose.pose.position.y-current_pose.getOrigin().getY()),2));
357  angle = calculateGlobalPlanAngle(current_pose, global_plan_, max_point);
358 
359  //check if max velocity is exceeded
360  if((distance/config_.sim_time) > config_.max_x_vel)
361  {
362  cmd_vel_linear_x_ = config_.max_x_vel;
363  }
364  else
365  {
366  cmd_vel_linear_x_ = (distance/config_.sim_time);
367  }
368 
369  //check if max rotation velocity is exceeded
370  if(fabs(angle/config_.sim_time)>config_.max_rotation_vel)
371  {
372  cmd_vel_angular_z_ = config_.max_rotation_vel;
373  }
374  else
375  {
376  cmd_vel_angular_z_ = (angle/config_.sim_time);
377  }
378 
379  //Calculate new velocity with max acceleration
380  if(cmd_vel_linear_x_ > cmd_vel_linear_x_old+config_.acceleration_x/config_.local_planner_frequence)
381  {
382  cmd_vel_linear_x_ = cmd_vel_linear_x_old+config_.acceleration_x/config_.local_planner_frequence;
383  }
384  else
385  {
386  if(cmd_vel_linear_x_ < cmd_vel_linear_x_old-config_.acceleration_x/config_.local_planner_frequence)
387  {
388  cmd_vel_linear_x_ = cmd_vel_linear_x_old-config_.acceleration_x/config_.local_planner_frequence;
389  }
390  else
391  {
392  cmd_vel_linear_x_ = cmd_vel_linear_x_old;
393  }
394  }
395 
396  //Calculate new velocity with max acceleration
397  if(fabs(cmd_vel_angular_z_) > fabs(cmd_vel_angular_z_old)+fabs(config_.acceleration_z/config_.local_planner_frequence))
398  {
399  if(cmd_vel_angular_z_ < 0)
400  {
401  cmd_vel_angular_z_ = cmd_vel_angular_z_old-config_.acceleration_z/config_.local_planner_frequence;
402  }
403  else
404  {
405  cmd_vel_angular_z_ = cmd_vel_angular_z_old+config_.acceleration_z/config_.local_planner_frequence;
406  }
407  }
408 
409  if(cmd_vel_angular_z_ < 0 && cmd_vel_angular_z_old > 0)
410  {
411  if( fabs(cmd_vel_angular_z_ - cmd_vel_angular_z_old) > fabs(config_.acceleration_z/config_.local_planner_frequence))
412  {
413  cmd_vel_angular_z_ = cmd_vel_angular_z_old - config_.acceleration_z/config_.local_planner_frequence;
414  }
415  }
416 
417  if(cmd_vel_angular_z_ > 0 && cmd_vel_angular_z_old < 0)
418  {
419  if( fabs(cmd_vel_angular_z_ - cmd_vel_angular_z_old) > fabs(config_.acceleration_z/config_.local_planner_frequence))
420  {
421  cmd_vel_angular_z_ = cmd_vel_angular_z_old + config_.acceleration_z/config_.local_planner_frequence;
422  }
423  }
424 
425  //Check at last if velocity is to high.
426  if(cmd_vel_angular_z_ > config_.max_rotation_vel)
427  {
428  cmd_vel_angular_z_ = config_.max_rotation_vel;
429  }
430  if(cmd_vel_angular_z_ < -config_.max_rotation_vel)
431  {
432  cmd_vel_angular_z_ = (- config_.max_rotation_vel);
433  }
434  if(cmd_vel_linear_x_ > config_.max_x_vel)
435  {
436  cmd_vel_linear_x_ = config_.max_x_vel;
437  }
438  //Push velocity to cmd_vel for driving.
439  cmd_vel.linear.x = cmd_vel_linear_x_;
440  cmd_vel.angular.z = cmd_vel_angular_z_;
441  cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_;
442  ROS_DEBUG("FTCPlanner: max_point: %d, distance: %f, x_vel: %f, rot_vel: %f, angle: %f", max_point, distance, cmd_vel.linear.x, cmd_vel.angular.z, angle);
443 
444  return max_point;
445  }
446 
447 
448  bool FTCPlanner::isGoalReached()
449  {
450  if(goal_reached_)
451  {
452  ROS_INFO("FTCPlanner: Goal reached.");
453  }
454  return goal_reached_;
455  }
456 
457  bool FTCPlanner::checkCollision(int max_points)
458  {
459  //maximal costs
460  unsigned char previous_cost = 255;
461 
462  for (int i = 0; i <= max_points; i++)
463  {
464  geometry_msgs::PoseStamped x_pose;
465  x_pose = transformed_global_plan_.at(i);
466 
467  unsigned int x;
468  unsigned int y;
469  costmap_ros_->getCostmap()->worldToMap(x_pose.pose.position.x, x_pose.pose.position.y, x, y);
470  unsigned char costs = costmap_ros_->getCostmap()->getCost(x, y);
471  //Near at obstacel
472  if(costs > 0)
473  {
474  if(!rotate_to_global_plan_)
475  {
476  ROS_INFO("FTCPlanner: Obstacel detected. Start routine new.");
477  }
478  rotate_to_global_plan_ = true;
479 
480  //Possible collision
481  if(costs > 127 && costs > previous_cost)
482  {
483  ROS_WARN("FTCPlanner: Possible collision. Stop local planner.");
484  return false;
485  }
486  }
487  previous_cost = costs;
488  }
489  return true;
490  }
491 
492  void FTCPlanner::publishPlan(int max_point)
493  {
494  std::vector<geometry_msgs::PoseStamped> path;
495  path = transformed_global_plan_;
496 
497  //given an empty path we won't do anything
498  if(path.empty())
499  return;
500 
501  //create a path message
502  nav_msgs::Path gui_path;
503  gui_path.poses.resize(path.size());
504  gui_path.header.frame_id = path[0].header.frame_id;
505  gui_path.header.stamp = path[0].header.stamp;
506 
507  // Extract the plan in world co-ordinates, we assume the path is all in the same frame
508  for(unsigned int i=0; i < path.size(); i++)
509  {
510  gui_path.poses[i] = path[i];
511  }
512 
513  local_plan_publisher_.publish(gui_path);
514  }
515 
516  FTCPlanner::~FTCPlanner()
517  {
518  }
519 }
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
static double getYaw(const Quaternion &bt_q)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
tf::TransformListener * tf_
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
double distance(double x0, double y0, double x1, double y1)
#define ROS_INFO(...)
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static Time now()
bool getXPose(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, tf::Stamped< tf::Pose > &goal_pose, int plan_point)
Returns X pose in plan.
def shortest_angular_distance(from_angle, to_angle)
#define ROS_DEBUG(...)


asr_ftc_local_planner
Author(s): Marek Felix
autogenerated on Mon Jun 17 2019 19:56:22