teb_local_planner_ros.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
40 
42 
43 #include <boost/algorithm/string.hpp>
44 
45 // pluginlib macros
47 
48 #include "g2o/core/sparse_optimizer.h"
49 #include "g2o/core/block_solver.h"
50 #include "g2o/core/factory.h"
51 #include "g2o/core/optimization_algorithm_gauss_newton.h"
52 #include "g2o/core/optimization_algorithm_levenberg.h"
53 #include "g2o/solvers/csparse/linear_solver_csparse.h"
54 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
55 
56 
57 // register this planner as a BaseLocalPlanner plugin
59 
60 namespace teb_local_planner
61 {
62 
63 
64 TebLocalPlannerROS::TebLocalPlannerROS() : costmap_ros_(NULL), tf_(NULL), costmap_model_(NULL),
65  costmap_converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"),
66  dynamic_recfg_(NULL), custom_via_points_active_(false), goal_reached_(false), no_infeasible_plans_(0),
67  last_preferred_rotdir_(RotType::none), initialized_(false)
68 {
69 }
70 
71 
73 {
74 }
75 
76 void TebLocalPlannerROS::reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level)
77 {
78  cfg_.reconfigure(config);
79 }
80 
82 {
83  // check if the plugin is already initialized
84  if(!initialized_)
85  {
86  // create Node Handle with name of plugin (as used in move_base for loading)
87  ros::NodeHandle nh("~/" + name);
88 
89  // get parameters of TebConfig via the nodehandle and override the default config
91 
92  // reserve some memory for obstacles
93  obstacles_.reserve(500);
94 
95  // create visualization instance
97 
98  // create robot footprint/contour model for optimization
100 
101  // create the planner instance
103  {
105  ROS_INFO("Parallel planning in distinctive topologies enabled.");
106  }
107  else
108  {
110  ROS_INFO("Parallel planning in distinctive topologies disabled.");
111  }
112 
113  // init other variables
114  tf_ = tf;
115  costmap_ros_ = costmap_ros;
116  costmap_ = costmap_ros_->getCostmap(); // locking should be done in MoveBase.
117 
118  costmap_model_ = boost::make_shared<base_local_planner::CostmapModel>(*costmap_);
119 
121  cfg_.map_frame = global_frame_; // TODO
123 
124  //Initialize a costmap to polygon converter
126  {
127  try
128  {
131  // replace '::' by '/' to convert the c++ namespace to a NodeHandle namespace
132  boost::replace_all(converter_name, "::", "/");
133  costmap_converter_->setOdomTopic(cfg_.odom_topic);
134  costmap_converter_->initialize(ros::NodeHandle(nh, "costmap_converter/" + converter_name));
135  costmap_converter_->setCostmap2D(costmap_);
136 
138  ROS_INFO_STREAM("Costmap conversion plugin " << cfg_.obstacles.costmap_converter_plugin << " loaded.");
139  }
141  {
142  ROS_WARN("The specified costmap converter plugin cannot be loaded. All occupied costmap cells are treaten as point obstacles. Error message: %s", ex.what());
143  costmap_converter_.reset();
144  }
145  }
146  else
147  ROS_INFO("No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.");
148 
149 
150  // Get footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices.
153 
154  // init the odom helper to receive the robot's velocity from odom messages
156 
157  // setup dynamic reconfigure
158  dynamic_recfg_ = boost::make_shared< dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig> >(nh);
159  dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig>::CallbackType cb = boost::bind(&TebLocalPlannerROS::reconfigureCB, this, _1, _2);
160  dynamic_recfg_->setCallback(cb);
161 
162  // validate optimization footprint and costmap footprint
163  validateFootprints(robot_model->getInscribedRadius(), robot_inscribed_radius_, cfg_.obstacles.min_obstacle_dist);
164 
165  // setup callback for custom obstacles
167 
168  // setup callback for custom via-points
170 
171  // initialize failure detector
172  ros::NodeHandle nh_move_base("~");
173  double controller_frequency = 5;
174  nh_move_base.param("controller_frequency", controller_frequency, controller_frequency);
176 
177  // set initialized flag
178  initialized_ = true;
179 
180  ROS_DEBUG("teb_local_planner plugin initialized.");
181  }
182  else
183  {
184  ROS_WARN("teb_local_planner has already been initialized, doing nothing.");
185  }
186 }
187 
188 
189 
190 bool TebLocalPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
191 {
192  // check if plugin is initialized
193  if(!initialized_)
194  {
195  ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner");
196  return false;
197  }
198 
199  // store the global plan
200  global_plan_.clear();
201  global_plan_ = orig_global_plan;
202 
203  // we do not clear the local planner here, since setPlan is called frequently whenever the global planner updates the plan.
204  // the local planner checks whether it is required to reinitialize the trajectory or not within each velocity computation step.
205 
206  // reset goal_reached_ flag
207  goal_reached_ = false;
208 
209  return true;
210 }
211 
212 
214 {
215  // check if plugin initialized
216  if(!initialized_)
217  {
218  ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner");
219  return false;
220  }
221 
222  cmd_vel.linear.x = 0;
223  cmd_vel.linear.y = 0;
224  cmd_vel.angular.z = 0;
225  goal_reached_ = false;
226 
227  // Get robot pose
228  tf::Stamped<tf::Pose> robot_pose;
229  costmap_ros_->getRobotPose(robot_pose);
230  robot_pose_ = PoseSE2(robot_pose);
231 
232  // Get robot velocity
233  tf::Stamped<tf::Pose> robot_vel_tf;
234  odom_helper_.getRobotVel(robot_vel_tf);
235  robot_vel_.linear.x = robot_vel_tf.getOrigin().getX();
236  robot_vel_.linear.y = robot_vel_tf.getOrigin().getY();
237  robot_vel_.angular.z = tf::getYaw(robot_vel_tf.getRotation());
238 
239  // prune global plan to cut off parts of the past (spatially before the robot)
241 
242  // Transform global plan to the frame of interest (w.r.t. the local costmap)
243  std::vector<geometry_msgs::PoseStamped> transformed_plan;
244  int goal_idx;
245  tf::StampedTransform tf_plan_to_global;
247  transformed_plan, &goal_idx, &tf_plan_to_global))
248  {
249  ROS_WARN("Could not transform the global plan to the frame of the controller");
250  return false;
251  }
252 
253  // update via-points container
256 
257  // check if global goal is reached
258  tf::Stamped<tf::Pose> global_goal;
259  tf::poseStampedMsgToTF(global_plan_.back(), global_goal);
260  global_goal.setData( tf_plan_to_global * global_goal );
261  double dx = global_goal.getOrigin().getX() - robot_pose_.x();
262  double dy = global_goal.getOrigin().getY() - robot_pose_.y();
263  double delta_orient = g2o::normalize_theta( tf::getYaw(global_goal.getRotation()) - robot_pose_.theta() );
264  if(fabs(std::sqrt(dx*dx+dy*dy)) < cfg_.goal_tolerance.xy_goal_tolerance
265  && fabs(delta_orient) < cfg_.goal_tolerance.yaw_goal_tolerance
267  {
268  goal_reached_ = true;
269  return true;
270  }
271 
272 
273  // check if we should enter any backup mode and apply settings
274  configureBackupModes(transformed_plan, goal_idx);
275 
276 
277  // Return false if the transformed global plan is empty
278  if (transformed_plan.empty())
279  {
280  ROS_WARN("Transformed plan is empty. Cannot determine a local plan.");
281  return false;
282  }
283 
284  // Get current goal point (last point of the transformed plan)
285  tf::Stamped<tf::Pose> goal_point;
286  tf::poseStampedMsgToTF(transformed_plan.back(), goal_point);
287  robot_goal_.x() = goal_point.getOrigin().getX();
288  robot_goal_.y() = goal_point.getOrigin().getY();
290  {
291  robot_goal_.theta() = estimateLocalGoalOrientation(global_plan_, goal_point, goal_idx, tf_plan_to_global);
292  // overwrite/update goal orientation of the transformed plan with the actual goal (enable using the plan as initialization)
293  transformed_plan.back().pose.orientation = tf::createQuaternionMsgFromYaw(robot_goal_.theta());
294  }
295  else
296  {
297  robot_goal_.theta() = tf::getYaw(goal_point.getRotation());
298  }
299 
300  // overwrite/update start of the transformed plan with the actual robot position (allows using the plan as initial trajectory)
301  if (transformed_plan.size()==1) // plan only contains the goal
302  {
303  transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped()); // insert start (not yet initialized)
304  }
305  tf::poseTFToMsg(robot_pose, transformed_plan.front().pose); // update start;
306 
307  // clear currently existing obstacles
308  obstacles_.clear();
309 
310  // Update obstacle container with costmap information or polygons provided by a costmap_converter plugin
311  if (costmap_converter_)
313  else
315 
316  // also consider custom obstacles (must be called after other updates, since the container is not cleared)
318 
319 
320  // Do not allow config changes during the following optimization step
321  boost::mutex::scoped_lock cfg_lock(cfg_.configMutex());
322 
323  // Now perform the actual planning
324 // bool success = planner_->plan(robot_pose_, robot_goal_, robot_vel_, cfg_.goal_tolerance.free_goal_vel); // straight line init
325  bool success = planner_->plan(transformed_plan, &robot_vel_, cfg_.goal_tolerance.free_goal_vel);
326  if (!success)
327  {
328  planner_->clearPlanner(); // force reinitialization for next time
329  ROS_WARN("teb_local_planner was not able to obtain a local plan for the current setting.");
330 
331  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
333  last_cmd_ = cmd_vel;
334  return false;
335  }
336 
337  // Check feasibility (but within the first few states only)
339  {
340  // Update footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices.
343  }
344 
346  if (!feasible)
347  {
348  cmd_vel.linear.x = 0;
349  cmd_vel.linear.y = 0;
350  cmd_vel.angular.z = 0;
351 
352  // now we reset everything to start again with the initialization of new trajectories.
353  planner_->clearPlanner();
354  ROS_WARN("TebLocalPlannerROS: trajectory is not feasible. Resetting planner...");
355 
356  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
358  last_cmd_ = cmd_vel;
359  return false;
360  }
361 
362  // Get the velocity command for this sampling interval
363  if (!planner_->getVelocityCommand(cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z, cfg_.trajectory.control_look_ahead_poses))
364  {
365  planner_->clearPlanner();
366  ROS_WARN("TebLocalPlannerROS: velocity command invalid. Resetting planner...");
367  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
369  last_cmd_ = cmd_vel;
370  return false;
371  }
372 
373  // Saturate velocity, if the optimization results violates the constraints (could be possible due to soft constraints).
374  saturateVelocity(cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z, cfg_.robot.max_vel_x, cfg_.robot.max_vel_y,
376 
377  // convert rot-vel to steering angle if desired (carlike robot).
378  // The min_turning_radius is allowed to be slighly smaller since it is a soft-constraint
379  // and opposed to the other constraints not affected by penalty_epsilon. The user might add a safety margin to the parameter itself.
381  {
382  cmd_vel.angular.z = convertTransRotVelToSteeringAngle(cmd_vel.linear.x, cmd_vel.angular.z, cfg_.robot.wheelbase, 0.95*cfg_.robot.min_turning_radius);
383  if (!std::isfinite(cmd_vel.angular.z))
384  {
385  cmd_vel.linear.x = cmd_vel.linear.y = cmd_vel.angular.z = 0;
386  last_cmd_ = cmd_vel;
387  planner_->clearPlanner();
388  ROS_WARN("TebLocalPlannerROS: Resulting steering angle is not finite. Resetting planner...");
389  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
391  return false;
392  }
393  }
394 
395  // a feasible solution should be found, reset counter
397 
398  // store last command (for recovery analysis etc.)
399  last_cmd_ = cmd_vel;
400 
401  // Now visualize everything
402  planner_->visualize();
403  visualization_->publishObstacles(obstacles_);
404  visualization_->publishViaPoints(via_points_);
405  visualization_->publishGlobalPlan(global_plan_);
406  return true;
407 }
408 
409 
411 {
412  if (goal_reached_)
413  {
414  ROS_INFO("GOAL Reached!");
415  planner_->clearPlanner();
416  return true;
417  }
418  return false;
419 }
420 
421 
422 
424 {
425  // Add costmap obstacles if desired
427  {
428  Eigen::Vector2d robot_orient = robot_pose_.orientationUnitVec();
429 
430  for (unsigned int i=0; i<costmap_->getSizeInCellsX()-1; ++i)
431  {
432  for (unsigned int j=0; j<costmap_->getSizeInCellsY()-1; ++j)
433  {
435  {
436  Eigen::Vector2d obs;
437  costmap_->mapToWorld(i,j,obs.coeffRef(0), obs.coeffRef(1));
438 
439  // check if obstacle is interesting (e.g. not far behind the robot)
440  Eigen::Vector2d obs_dir = obs-robot_pose_.position();
441  if ( obs_dir.dot(robot_orient) < 0 && obs_dir.norm() > cfg_.obstacles.costmap_obstacles_behind_robot_dist )
442  continue;
443 
444  obstacles_.push_back(ObstaclePtr(new PointObstacle(obs)));
445  }
446  }
447  }
448  }
449 }
450 
452 {
453  if (!costmap_converter_)
454  return;
455 
456  //Get obstacles from costmap converter
458  if (!obstacles)
459  return;
460 
461  for (std::size_t i=0; i<obstacles->obstacles.size(); ++i)
462  {
463  const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i);
464  const geometry_msgs::Polygon* polygon = &obstacle->polygon;
465 
466  if (polygon->points.size()==1 && obstacle->radius > 0) // Circle
467  {
468  obstacles_.push_back(ObstaclePtr(new CircularObstacle(polygon->points[0].x, polygon->points[0].y, obstacle->radius)));
469  }
470  else if (polygon->points.size()==1) // Point
471  {
472  obstacles_.push_back(ObstaclePtr(new PointObstacle(polygon->points[0].x, polygon->points[0].y)));
473  }
474  else if (polygon->points.size()==2) // Line
475  {
476  obstacles_.push_back(ObstaclePtr(new LineObstacle(polygon->points[0].x, polygon->points[0].y,
477  polygon->points[1].x, polygon->points[1].y )));
478  }
479  else if (polygon->points.size()>2) // Real polygon
480  {
481  PolygonObstacle* polyobst = new PolygonObstacle;
482  for (std::size_t j=0; j<polygon->points.size(); ++j)
483  {
484  polyobst->pushBackVertex(polygon->points[j].x, polygon->points[j].y);
485  }
486  polyobst->finalizePolygon();
487  obstacles_.push_back(ObstaclePtr(polyobst));
488  }
489 
490  // Set velocity, if obstacle is moving
491  if(!obstacles_.empty())
492  obstacles_.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation);
493  }
494 }
495 
496 
498 {
499  // Add custom obstacles obtained via message
500  boost::mutex::scoped_lock l(custom_obst_mutex_);
501 
502  if (!custom_obstacle_msg_.obstacles.empty())
503  {
504  // We only use the global header to specify the obstacle coordinate system instead of individual ones
505  Eigen::Affine3d obstacle_to_map_eig;
506  try
507  {
508  tf::StampedTransform obstacle_to_map;
510  custom_obstacle_msg_.header.frame_id, ros::Time(0),
511  custom_obstacle_msg_.header.frame_id, ros::Duration(0.5));
513  custom_obstacle_msg_.header.frame_id, ros::Time(0),
514  custom_obstacle_msg_.header.frame_id, obstacle_to_map);
515  tf::transformTFToEigen(obstacle_to_map, obstacle_to_map_eig);
516  }
517  catch (tf::TransformException ex)
518  {
519  ROS_ERROR("%s",ex.what());
520  obstacle_to_map_eig.setIdentity();
521  }
522 
523  for (size_t i=0; i<custom_obstacle_msg_.obstacles.size(); ++i)
524  {
525  if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 1 && custom_obstacle_msg_.obstacles.at(i).radius > 0 ) // circle
526  {
527  Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x,
528  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y,
529  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z );
530  obstacles_.push_back(ObstaclePtr(new CircularObstacle( (obstacle_to_map_eig * pos).head(2), custom_obstacle_msg_.obstacles.at(i).radius)));
531  }
532  else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 1 ) // point
533  {
534  Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x,
535  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y,
536  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z );
537  obstacles_.push_back(ObstaclePtr(new PointObstacle( (obstacle_to_map_eig * pos).head(2) )));
538  }
539  else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 2 ) // line
540  {
541  Eigen::Vector3d line_start( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x,
542  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y,
543  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z );
544  Eigen::Vector3d line_end( custom_obstacle_msg_.obstacles.at(i).polygon.points.back().x,
545  custom_obstacle_msg_.obstacles.at(i).polygon.points.back().y,
546  custom_obstacle_msg_.obstacles.at(i).polygon.points.back().z );
547  obstacles_.push_back(ObstaclePtr(new LineObstacle( (obstacle_to_map_eig * line_start).head(2),
548  (obstacle_to_map_eig * line_end).head(2) )));
549  }
550  else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.empty())
551  {
552  ROS_WARN("Invalid custom obstacle received. List of polygon vertices is empty. Skipping...");
553  continue;
554  }
555  else // polygon
556  {
557  PolygonObstacle* polyobst = new PolygonObstacle;
558  for (size_t j=0; j<custom_obstacle_msg_.obstacles.at(i).polygon.points.size(); ++j)
559  {
560  Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points[j].x,
561  custom_obstacle_msg_.obstacles.at(i).polygon.points[j].y,
562  custom_obstacle_msg_.obstacles.at(i).polygon.points[j].z );
563  polyobst->pushBackVertex( (obstacle_to_map_eig * pos).head(2) );
564  }
565  polyobst->finalizePolygon();
566  obstacles_.push_back(ObstaclePtr(polyobst));
567  }
568 
569  // Set velocity, if obstacle is moving
570  if(!obstacles_.empty())
571  obstacles_.back()->setCentroidVelocity(custom_obstacle_msg_.obstacles[i].velocities, custom_obstacle_msg_.obstacles[i].orientation);
572  }
573  }
574 }
575 
576 void TebLocalPlannerROS::updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation)
577 {
578  via_points_.clear();
579 
580  if (min_separation<=0)
581  return;
582 
583  std::size_t prev_idx = 0;
584  for (std::size_t i=1; i < transformed_plan.size(); ++i) // skip first one, since we do not need any point before the first min_separation [m]
585  {
586  // check separation to the previous via-point inserted
587  if (distance_points2d( transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position ) < min_separation)
588  continue;
589 
590  // add via-point
591  via_points_.push_back( Eigen::Vector2d( transformed_plan[i].pose.position.x, transformed_plan[i].pose.position.y ) );
592  prev_idx = i;
593  }
594 
595 }
596 
598 {
599  Eigen::Vector2d vel;
600  vel.coeffRef(0) = std::sqrt( tf_vel.getOrigin().getX() * tf_vel.getOrigin().getX() + tf_vel.getOrigin().getY() * tf_vel.getOrigin().getY() );
601  vel.coeffRef(1) = tf::getYaw(tf_vel.getRotation());
602  return vel;
603 }
604 
605 
606 bool TebLocalPlannerROS::pruneGlobalPlan(const tf::TransformListener& tf, const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot)
607 {
608  if (global_plan.empty())
609  return true;
610 
611  try
612  {
613  // transform robot pose into the plan frame (we do not wait here, since pruning not crucial, if missed a few times)
614  tf::StampedTransform global_to_plan_transform;
615  tf.lookupTransform(global_plan.front().header.frame_id, global_pose.frame_id_, ros::Time(0), global_to_plan_transform);
616  tf::Stamped<tf::Pose> robot;
617  robot.setData( global_to_plan_transform * global_pose );
618 
619  double dist_thresh_sq = dist_behind_robot*dist_behind_robot;
620 
621  // iterate plan until a pose close the robot is found
622  std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin();
623  std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it;
624  while (it != global_plan.end())
625  {
626  double dx = robot.getOrigin().x() - it->pose.position.x;
627  double dy = robot.getOrigin().y() - it->pose.position.y;
628  double dist_sq = dx * dx + dy * dy;
629  if (dist_sq < dist_thresh_sq)
630  {
631  erase_end = it;
632  break;
633  }
634  ++it;
635  }
636  if (erase_end == global_plan.end())
637  return false;
638 
639  if (erase_end != global_plan.begin())
640  global_plan.erase(global_plan.begin(), erase_end);
641  }
642  catch (const tf::TransformException& ex)
643  {
644  ROS_DEBUG("Cannot prune path since no transform is available: %s\n", ex.what());
645  return false;
646  }
647  return true;
648 }
649 
650 
651 bool TebLocalPlannerROS::transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
652  const tf::Stamped<tf::Pose>& global_pose, const costmap_2d::Costmap2D& costmap, const std::string& global_frame, double max_plan_length,
653  std::vector<geometry_msgs::PoseStamped>& transformed_plan, int* current_goal_idx, tf::StampedTransform* tf_plan_to_global) const
654 {
655  // this method is a slightly modified version of base_local_planner/goal_functions.h
656 
657  const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
658 
659  transformed_plan.clear();
660 
661  try
662  {
663  if (global_plan.empty())
664  {
665  ROS_ERROR("Received plan with zero length");
666  *current_goal_idx = 0;
667  return false;
668  }
669 
670  // get plan_to_global_transform from plan frame to global_frame
671  tf::StampedTransform plan_to_global_transform;
672  tf.waitForTransform(global_frame, ros::Time::now(),
673  plan_pose.header.frame_id, plan_pose.header.stamp,
674  plan_pose.header.frame_id, ros::Duration(0.5));
675  tf.lookupTransform(global_frame, ros::Time(),
676  plan_pose.header.frame_id, plan_pose.header.stamp,
677  plan_pose.header.frame_id, plan_to_global_transform);
678 
679  //let's get the pose of the robot in the frame of the plan
680  tf::Stamped<tf::Pose> robot_pose;
681  tf.transformPose(plan_pose.header.frame_id, global_pose, robot_pose);
682 
683  //we'll discard points on the plan that are outside the local costmap
684  double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0,
685  costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
686  dist_threshold *= 0.85; // just consider 85% of the costmap size to better incorporate point obstacle that are
687  // located on the border of the local costmap
688 
689 
690  int i = 0;
691  double sq_dist_threshold = dist_threshold * dist_threshold;
692  double sq_dist = 1e10;
693 
694  //we need to loop to a point on the plan that is within a certain distance of the robot
695  for(int j=0; j < (int)global_plan.size(); ++j)
696  {
697  double x_diff = robot_pose.getOrigin().x() - global_plan[j].pose.position.x;
698  double y_diff = robot_pose.getOrigin().y() - global_plan[j].pose.position.y;
699  double new_sq_dist = x_diff * x_diff + y_diff * y_diff;
700  if (new_sq_dist > sq_dist_threshold)
701  break; // force stop if we have reached the costmap border
702 
703  if (new_sq_dist < sq_dist) // find closest distance
704  {
705  sq_dist = new_sq_dist;
706  i = j;
707  }
708  }
709 
710  tf::Stamped<tf::Pose> tf_pose;
711  geometry_msgs::PoseStamped newer_pose;
712 
713  double plan_length = 0; // check cumulative Euclidean distance along the plan
714 
715  //now we'll transform until points are outside of our distance threshold
716  while(i < (int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length<=0 || plan_length <= max_plan_length))
717  {
718  const geometry_msgs::PoseStamped& pose = global_plan[i];
719  tf::poseStampedMsgToTF(pose, tf_pose);
720  tf_pose.setData(plan_to_global_transform * tf_pose);
721  tf_pose.stamp_ = plan_to_global_transform.stamp_;
722  tf_pose.frame_id_ = global_frame;
723  tf::poseStampedTFToMsg(tf_pose, newer_pose);
724 
725  transformed_plan.push_back(newer_pose);
726 
727  double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
728  double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
729  sq_dist = x_diff * x_diff + y_diff * y_diff;
730 
731  // caclulate distance to previous pose
732  if (i>0 && max_plan_length>0)
733  plan_length += distance_points2d(global_plan[i-1].pose.position, global_plan[i].pose.position);
734 
735  ++i;
736  }
737 
738  // if we are really close to the goal (<sq_dist_threshold) and the goal is not yet reached (e.g. orientation error >>0)
739  // the resulting transformed plan can be empty. In that case we explicitly inject the global goal.
740  if (transformed_plan.empty())
741  {
742  tf::poseStampedMsgToTF(global_plan.back(), tf_pose);
743  tf_pose.setData(plan_to_global_transform * tf_pose);
744  tf_pose.stamp_ = plan_to_global_transform.stamp_;
745  tf_pose.frame_id_ = global_frame;
746  tf::poseStampedTFToMsg(tf_pose, newer_pose);
747 
748  transformed_plan.push_back(newer_pose);
749 
750  // Return the index of the current goal point (inside the distance threshold)
751  if (current_goal_idx) *current_goal_idx = int(global_plan.size())-1;
752  }
753  else
754  {
755  // Return the index of the current goal point (inside the distance threshold)
756  if (current_goal_idx) *current_goal_idx = i-1; // subtract 1, since i was increased once before leaving the loop
757  }
758 
759  // Return the transformation from the global plan to the global planning frame if desired
760  if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform;
761  }
762  catch(tf::LookupException& ex)
763  {
764  ROS_ERROR("No Transform available Error: %s\n", ex.what());
765  return false;
766  }
767  catch(tf::ConnectivityException& ex)
768  {
769  ROS_ERROR("Connectivity Error: %s\n", ex.what());
770  return false;
771  }
772  catch(tf::ExtrapolationException& ex)
773  {
774  ROS_ERROR("Extrapolation Error: %s\n", ex.what());
775  if (global_plan.size() > 0)
776  ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
777 
778  return false;
779  }
780 
781  return true;
782 }
783 
784 
785 
786 
787 double TebLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan, const tf::Stamped<tf::Pose>& local_goal,
788  int current_goal_idx, const tf::StampedTransform& tf_plan_to_global, int moving_average_length) const
789 {
790  int n = (int)global_plan.size();
791 
792  // check if we are near the global goal already
793  if (current_goal_idx > n-moving_average_length-2)
794  {
795  if (current_goal_idx >= n-1) // we've exactly reached the goal
796  {
797  return tf::getYaw(local_goal.getRotation());
798  }
799  else
800  {
801  tf::Quaternion global_orientation;
802  tf::quaternionMsgToTF(global_plan.back().pose.orientation, global_orientation);
803  return tf::getYaw(tf_plan_to_global.getRotation() * global_orientation );
804  }
805  }
806 
807  // reduce number of poses taken into account if the desired number of poses is not available
808  moving_average_length = std::min(moving_average_length, n-current_goal_idx-1 ); // maybe redundant, since we have checked the vicinity of the goal before
809 
810  std::vector<double> candidates;
811  tf::Stamped<tf::Pose> tf_pose_k = local_goal;
812  tf::Stamped<tf::Pose> tf_pose_kp1;
813 
814  int range_end = current_goal_idx + moving_average_length;
815  for (int i = current_goal_idx; i < range_end; ++i)
816  {
817  // Transform pose of the global plan to the planning frame
818  const geometry_msgs::PoseStamped& pose = global_plan.at(i+1);
819  tf::poseStampedMsgToTF(pose, tf_pose_kp1);
820  tf_pose_kp1.setData(tf_plan_to_global * tf_pose_kp1);
821 
822  // calculate yaw angle
823  candidates.push_back( std::atan2(tf_pose_kp1.getOrigin().getY() - tf_pose_k.getOrigin().getY(),
824  tf_pose_kp1.getOrigin().getX() - tf_pose_k.getOrigin().getX() ) );
825 
826  if (i<range_end-1)
827  tf_pose_k = tf_pose_kp1;
828  }
829  return average_angles(candidates);
830 }
831 
832 
833 void TebLocalPlannerROS::saturateVelocity(double& vx, double& vy, double& omega, double max_vel_x, double max_vel_y, double max_vel_theta, double max_vel_x_backwards) const
834 {
835  // Limit translational velocity for forward driving
836  if (vx > max_vel_x)
837  vx = max_vel_x;
838 
839  // limit strafing velocity
840  if (vy > max_vel_y)
841  vy = max_vel_y;
842  else if (vy < -max_vel_y)
843  vy = -max_vel_y;
844 
845  // Limit angular velocity
846  if (omega > max_vel_theta)
847  omega = max_vel_theta;
848  else if (omega < -max_vel_theta)
849  omega = -max_vel_theta;
850 
851  // Limit backwards velocity
852  if (max_vel_x_backwards<=0)
853  {
854  ROS_WARN_ONCE("TebLocalPlannerROS(): Do not choose max_vel_x_backwards to be <=0. Disable backwards driving by increasing the optimization weight for penalyzing backwards driving.");
855  }
856  else if (vx < -max_vel_x_backwards)
857  vx = -max_vel_x_backwards;
858 }
859 
860 
861 double TebLocalPlannerROS::convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius) const
862 {
863  if (omega==0 || v==0)
864  return 0;
865 
866  double radius = v/omega;
867 
868  if (fabs(radius) < min_turning_radius)
869  radius = double(g2o::sign(radius)) * min_turning_radius;
870 
871  return std::atan(wheelbase / radius);
872 }
873 
874 
875 void TebLocalPlannerROS::validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist)
876 {
877  ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius,
878  "The inscribed radius of the footprint specified for TEB optimization (%f) + min_obstacle_dist (%f) are smaller "
879  "than the inscribed radius of the robot's footprint in the costmap parameters (%f, including 'footprint_padding'). "
880  "Infeasible optimziation results might occur frequently!", opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius);
881 }
882 
883 
884 
885 void TebLocalPlannerROS::configureBackupModes(std::vector<geometry_msgs::PoseStamped>& transformed_plan, int& goal_idx)
886 {
887  ros::Time current_time = ros::Time::now();
888 
889  // reduced horizon backup mode
891  goal_idx < (int)transformed_plan.size()-1 && // we do not reduce if the goal is already selected (because the orientation might change -> can introduce oscillations)
892  (no_infeasible_plans_>0 || (current_time - time_last_infeasible_plan_).toSec() < cfg_.recovery.shrink_horizon_min_duration )) // keep short horizon for at least a few seconds
893  {
894  ROS_INFO_COND(no_infeasible_plans_==1, "Activating reduced horizon backup mode for at least %.2f sec (infeasible trajectory detected).", cfg_.recovery.shrink_horizon_min_duration);
895 
896 
897  // Shorten horizon if requested
898  // reduce to 50 percent:
899  int horizon_reduction = goal_idx/2;
900 
901  if (no_infeasible_plans_ > 9)
902  {
903  ROS_INFO_COND(no_infeasible_plans_==10, "Infeasible trajectory detected 10 times in a row: further reducing horizon...");
904  horizon_reduction /= 2;
905  }
906 
907  // we have a small overhead here, since we already transformed 50% more of the trajectory.
908  // But that's ok for now, since we do not need to make transformGlobalPlan more complex
909  // and a reduced horizon should occur just rarely.
910  int new_goal_idx_transformed_plan = int(transformed_plan.size()) - horizon_reduction - 1;
911  goal_idx -= horizon_reduction;
912  if (new_goal_idx_transformed_plan>0 && goal_idx >= 0)
913  transformed_plan.erase(transformed_plan.begin()+new_goal_idx_transformed_plan, transformed_plan.end());
914  else
915  goal_idx += horizon_reduction; // this should not happen, but safety first ;-)
916  }
917 
918 
919  // detect and resolve oscillations
921  {
922  double max_vel_theta;
923  double max_vel_current = last_cmd_.linear.x >= 0 ? cfg_.robot.max_vel_x : cfg_.robot.max_vel_x_backwards;
924  if (cfg_.robot.min_turning_radius!=0 && max_vel_current>0)
925  max_vel_theta = std::max( max_vel_current/std::abs(cfg_.robot.min_turning_radius), cfg_.robot.max_vel_theta );
926  else
927  max_vel_theta = cfg_.robot.max_vel_theta;
928 
931 
932  bool oscillating = failure_detector_.isOscillating();
933  bool recently_oscillated = (ros::Time::now()-time_last_oscillation_).toSec() < cfg_.recovery.oscillation_recovery_min_duration; // check if we have already detected an oscillation recently
934 
935  if (oscillating)
936  {
937  if (!recently_oscillated)
938  {
939  // save current turning direction
940  if (robot_vel_.angular.z > 0)
942  else
944  ROS_WARN("TebLocalPlannerROS: possible oscillation (of the robot or its local plan) detected. Activating recovery strategy (prefer current turning direction during optimization).");
945  }
947  planner_->setPreferredTurningDir(last_preferred_rotdir_);
948  }
949  else if (!recently_oscillated && last_preferred_rotdir_ != RotType::none) // clear recovery behavior
950  {
952  planner_->setPreferredTurningDir(last_preferred_rotdir_);
953  ROS_INFO("TebLocalPlannerROS: oscillation recovery disabled/expired.");
954  }
955  }
956 
957 }
958 
959 
960 void TebLocalPlannerROS::customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg)
961 {
962  boost::mutex::scoped_lock l(custom_obst_mutex_);
963  custom_obstacle_msg_ = *obst_msg;
964 }
965 
966 void TebLocalPlannerROS::customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg)
967 {
968  ROS_INFO_ONCE("Via-points received. This message is printed once.");
970  {
971  ROS_WARN("Via-points are already obtained from the global plan (global_plan_viapoint_sep>0)."
972  "Ignoring custom via-points.");
974  return;
975  }
976 
977  boost::mutex::scoped_lock l(via_point_mutex_);
978  via_points_.clear();
979  for (const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
980  {
981  via_points_.emplace_back(pose.pose.position.x, pose.pose.position.y);
982  }
984 }
985 
987 {
988  std::string model_name;
989  if (!nh.getParam("footprint_model/type", model_name))
990  {
991  ROS_INFO("No robot footprint model specified for trajectory optimization. Using point-shaped model.");
992  return boost::make_shared<PointRobotFootprint>();
993  }
994 
995  // point
996  if (model_name.compare("point") == 0)
997  {
998  ROS_INFO("Footprint model 'point' loaded for trajectory optimization.");
999  return boost::make_shared<PointRobotFootprint>();
1000  }
1001 
1002  // circular
1003  if (model_name.compare("circular") == 0)
1004  {
1005  // get radius
1006  double radius;
1007  if (!nh.getParam("footprint_model/radius", radius))
1008  {
1009  ROS_ERROR_STREAM("Footprint model 'circular' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1010  << "/footprint_model/radius' does not exist. Using point-model instead.");
1011  return boost::make_shared<PointRobotFootprint>();
1012  }
1013  ROS_INFO_STREAM("Footprint model 'circular' (radius: " << radius <<"m) loaded for trajectory optimization.");
1014  return boost::make_shared<CircularRobotFootprint>(radius);
1015  }
1016 
1017  // line
1018  if (model_name.compare("line") == 0)
1019  {
1020  // check parameters
1021  if (!nh.hasParam("footprint_model/line_start") || !nh.hasParam("footprint_model/line_end"))
1022  {
1023  ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1024  << "/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
1025  return boost::make_shared<PointRobotFootprint>();
1026  }
1027  // get line coordinates
1028  std::vector<double> line_start, line_end;
1029  nh.getParam("footprint_model/line_start", line_start);
1030  nh.getParam("footprint_model/line_end", line_end);
1031  if (line_start.size() != 2 || line_end.size() != 2)
1032  {
1033  ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1034  << "/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead.");
1035  return boost::make_shared<PointRobotFootprint>();
1036  }
1037 
1038  ROS_INFO_STREAM("Footprint model 'line' (line_start: [" << line_start[0] << "," << line_start[1] <<"]m, line_end: ["
1039  << line_end[0] << "," << line_end[1] << "]m) loaded for trajectory optimization.");
1040  return boost::make_shared<LineRobotFootprint>(Eigen::Map<const Eigen::Vector2d>(line_start.data()), Eigen::Map<const Eigen::Vector2d>(line_end.data()));
1041  }
1042 
1043  // two circles
1044  if (model_name.compare("two_circles") == 0)
1045  {
1046  // check parameters
1047  if (!nh.hasParam("footprint_model/front_offset") || !nh.hasParam("footprint_model/front_radius")
1048  || !nh.hasParam("footprint_model/rear_offset") || !nh.hasParam("footprint_model/rear_radius"))
1049  {
1050  ROS_ERROR_STREAM("Footprint model 'two_circles' cannot be loaded for trajectory optimization, since params '" << nh.getNamespace()
1051  << "/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using point-model instead.");
1052  return boost::make_shared<PointRobotFootprint>();
1053  }
1054  double front_offset, front_radius, rear_offset, rear_radius;
1055  nh.getParam("footprint_model/front_offset", front_offset);
1056  nh.getParam("footprint_model/front_radius", front_radius);
1057  nh.getParam("footprint_model/rear_offset", rear_offset);
1058  nh.getParam("footprint_model/rear_radius", rear_radius);
1059  ROS_INFO_STREAM("Footprint model 'two_circles' (front_offset: " << front_offset <<"m, front_radius: " << front_radius
1060  << "m, rear_offset: " << rear_offset << "m, rear_radius: " << rear_radius << "m) loaded for trajectory optimization.");
1061  return boost::make_shared<TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius);
1062  }
1063 
1064  // polygon
1065  if (model_name.compare("polygon") == 0)
1066  {
1067 
1068  // check parameters
1069  XmlRpc::XmlRpcValue footprint_xmlrpc;
1070  if (!nh.getParam("footprint_model/vertices", footprint_xmlrpc) )
1071  {
1072  ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1073  << "/footprint_model/vertices' does not exist. Using point-model instead.");
1074  return boost::make_shared<PointRobotFootprint>();
1075  }
1076  // get vertices
1077  if (footprint_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray)
1078  {
1079  try
1080  {
1081  Point2dContainer polygon = makeFootprintFromXMLRPC(footprint_xmlrpc, "/footprint_model/vertices");
1082  ROS_INFO_STREAM("Footprint model 'polygon' loaded for trajectory optimization.");
1083  return boost::make_shared<PolygonRobotFootprint>(polygon);
1084  }
1085  catch(const std::exception& ex)
1086  {
1087  ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization: " << ex.what() << ". Using point-model instead.");
1088  return boost::make_shared<PointRobotFootprint>();
1089  }
1090  }
1091  else
1092  {
1093  ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1094  << "/footprint_model/vertices' does not define an array of coordinates. Using point-model instead.");
1095  return boost::make_shared<PointRobotFootprint>();
1096  }
1097 
1098  }
1099 
1100  // otherwise
1101  ROS_WARN_STREAM("Unknown robot footprint model specified with parameter '" << nh.getNamespace() << "/footprint_model/type'. Using point model instead.");
1102  return boost::make_shared<PointRobotFootprint>();
1103 }
1104 
1105 
1106 
1107 
1108 Point2dContainer TebLocalPlannerROS::makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name)
1109 {
1110  // Make sure we have an array of at least 3 elements.
1111  if (footprint_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray ||
1112  footprint_xmlrpc.size() < 3)
1113  {
1114  ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s",
1115  full_param_name.c_str(), std::string(footprint_xmlrpc).c_str());
1116  throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least "
1117  "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
1118  }
1119 
1120  Point2dContainer footprint;
1121  Eigen::Vector2d pt;
1122 
1123  for (int i = 0; i < footprint_xmlrpc.size(); ++i)
1124  {
1125  // Make sure each element of the list is an array of size 2. (x and y coordinates)
1126  XmlRpc::XmlRpcValue point = footprint_xmlrpc[ i ];
1127  if (point.getType() != XmlRpc::XmlRpcValue::TypeArray ||
1128  point.size() != 2)
1129  {
1130  ROS_FATAL("The footprint (parameter %s) must be specified as list of lists on the parameter server eg: "
1131  "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.",
1132  full_param_name.c_str());
1133  throw std::runtime_error("The footprint must be specified as list of lists on the parameter server eg: "
1134  "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
1135  }
1136 
1137  pt.x() = getNumberFromXMLRPC(point[ 0 ], full_param_name);
1138  pt.y() = getNumberFromXMLRPC(point[ 1 ], full_param_name);
1139 
1140  footprint.push_back(pt);
1141  }
1142  return footprint;
1143 }
1144 
1145 double TebLocalPlannerROS::getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name)
1146 {
1147  // Make sure that the value we're looking at is either a double or an int.
1148  if (value.getType() != XmlRpc::XmlRpcValue::TypeInt &&
1150  {
1151  std::string& value_string = value;
1152  ROS_FATAL("Values in the footprint specification (param %s) must be numbers. Found value %s.",
1153  full_param_name.c_str(), value_string.c_str());
1154  throw std::runtime_error("Values in the footprint specification must be numbers");
1155  }
1156  return value.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(value) : (double)(value);
1157 }
1158 
1159 } // end namespace teb_local_planner
1160 
1161 
bool include_costmap_obstacles
Specify whether the obstacles in the costmap should be taken into account directly.
Definition: teb_config.h:123
bool cmd_angle_instead_rotvel
Substitute the rotational velocity in the commanded velocity message by the corresponding steering an...
Definition: teb_config.h:103
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it&#39;s subclasses.
Implements a 2D circular obstacle (point obstacle plus radius)
Definition: obstacles.h:447
boost::shared_ptr< dynamic_reconfigure::Server< TebLocalPlannerReconfigureConfig > > dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
bool isGoalReached()
Check if the goal pose has been achieved.
std::string map_frame
Global planning frame.
Definition: teb_config.h:66
TebVisualizationPtr visualization_
Instance of the visualization class (local/global plan, obstacles, ...)
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!) ...
Definition: teb_config.h:96
#define ROS_FATAL(...)
void finalizePolygon()
Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods...
Definition: obstacles.h:926
boost::mutex via_point_mutex_
Mutex that locks the via_points container (multi-threaded)
costmap_converter::ObstacleArrayMsg custom_obstacle_msg_
Copy of the most recent obstacle message.
TebConfig config
PoseSE2 robot_goal_
Store current robot goal.
void getRobotVel(tf::Stamped< tf::Pose > &robot_vel)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the teb plugin.
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
bool initialized_
Keeps track about the correct initialization of this class.
double min_obstacle_dist
Minimum desired separation from obstacles.
Definition: teb_config.h:119
void setData(const T &input)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
bool shrink_horizon_backup
Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues...
Definition: teb_config.h:204
#define ROS_INFO_ONCE(...)
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:145
double robot_circumscribed_radius
The radius of the circumscribed circle of the robot.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void updateViaPointsContainer(const std::vector< geometry_msgs::PoseStamped > &transformed_plan, double min_separation)
Update internal via-point container based on the current reference plan.
bool pruneGlobalPlan(const tf::TransformListener &tf, const tf::Stamped< tf::Pose > &global_pose, std::vector< geometry_msgs::PoseStamped > &global_plan, double dist_behind_robot=1)
Prune global plan such that already passed poses are cut off.
int size() const
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
boost::shared_ptr< base_local_planner::CostmapModel > costmap_model_
static double getYaw(const Quaternion &bt_q)
bool custom_via_points_active_
Keep track whether valid via-points have been received from via_points_sub_.
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
Definition: teb_config.h:111
double global_plan_viapoint_sep
Min. separation between each two consecutive via-points extracted from the global plan (if negative: ...
Definition: teb_config.h:78
void customViaPointsCB(const nav_msgs::Path::ConstPtr &via_points_msg)
Callback for custom via-points.
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > costmap_converter_loader_
Load costmap converter plugins at runtime.
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &global_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, double max_plan_length, std::vector< geometry_msgs::PoseStamped > &transformed_plan, int *current_goal_idx=NULL, tf::StampedTransform *tf_plan_to_global=NULL) const
Transforms the global plan of the robot from the planner frame to the local frame (modified)...
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
std::vector< geometry_msgs::Point > footprint_spec_
Store the footprint of the robot.
int no_infeasible_plans_
Store how many times in a row the planner failed to find a feasible plan.
Local planner that explores alternative homotopy classes, create a plan for each alternative and fina...
double yaw_goal_tolerance
Allowed final orientation error.
Definition: teb_config.h:110
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
Definition: teb_config.h:101
static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle &nh)
Get the current robot footprint/contour model.
FailureDetector failure_detector_
Detect if the robot got stucked.
TFSIMD_FORCE_INLINE const tfScalar & getY() const
bool goal_reached_
store whether the goal is reached or not
double & x()
Access the x-coordinate the pose.
Definition: pose_se2.h:158
void setBufferLength(int length)
Set buffer length (measurement history)
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
ros::Time time_last_infeasible_plan_
Store at which time stamp the last infeasible plan was detected.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
tf::TransformListener * tf_
Type const & getType() const
void updateObstacleContainerWithCostmapConverter()
Update internal obstacle vector based on polygons provided by a costmap_converter plugin...
ros::Subscriber custom_obst_sub_
Subscriber for custom obstacles received via a ObstacleMsg.
#define ROS_WARN(...)
Implements a polygon obstacle with an arbitrary number of vertices.
Definition: obstacles.h:748
Implements a 2D line obstacle.
Definition: obstacles.h:597
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:215
int feasibility_check_no_poses
Specify up to which pose on the predicted plan the feasibility should be checked each sampling interv...
Definition: teb_config.h:85
double costmap_obstacles_behind_robot_dist
Limit the occupied local costmap obstacles taken into account for planning behind the robot (specify ...
Definition: teb_config.h:124
struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
Goal tolerance related parameters.
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
boost::mutex custom_obst_mutex_
Mutex that locks the obstacle array (multi-threaded)
boost::shared_ptr< Obstacle > ObstaclePtr
Abbrev. for shared obstacle pointers.
Definition: obstacles.h:293
std::vector< geometry_msgs::PoseStamped > global_plan_
Store the current global plan.
void update(const geometry_msgs::Twist &twist, double v_max, double v_backwards_max, double omega_max, double v_eps, double omega_eps)
Add a new twist measurement to the internal buffer and compute a new decision.
void reconfigure(TebLocalPlannerReconfigureConfig &cfg)
Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e...
Definition: teb_config.cpp:170
unsigned char getCost(unsigned int mx, unsigned int my) const
void updateObstacleContainerWithCustomObstacles()
Update internal obstacle vector based on custom messages received via subscriber. ...
RotType
Symbols for left/none/right rotations.
Definition: misc.h:53
costmap_2d::Costmap2DROS * costmap_ros_
Pointer to the costmap ros wrapper, received from the navigation stack.
tf::TransformListener * tf_
pointer to Transform Listener
void loadRosParamFromNodeHandle(const ros::NodeHandle &nh)
Load parmeters from the ros param server.
Definition: teb_config.cpp:44
RotType last_preferred_rotdir_
Store recent preferred turning direction.
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
#define ROS_WARN_ONCE(...)
struct teb_local_planner::TebConfig::HomotopyClasses hcp
#define ROS_INFO(...)
std::string odom_topic
Topic name of the odometry message, provided by the robot driver or simulator.
Definition: teb_config.h:65
~TebLocalPlannerROS()
Destructor of the plugin.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
double estimateLocalGoalOrientation(const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &local_goal, int current_goal_idx, const tf::StampedTransform &tf_plan_to_global, int moving_average_length=3) const
Estimate the orientation of a pose from the global_plan that is treated as a local goal for the local...
Implements a 2D point obstacle.
Definition: obstacles.h:305
int control_look_ahead_poses
Min angular resolution used during the costmap collision check. If not respected, intermediate sample...
Definition: teb_config.h:88
std::string getBaseFrameID()
const std::string & getNamespace() const
TebConfig cfg_
Config class that stores and manages all related parameters.
static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
Set the footprint from the given XmlRpcValue.
bool enable_homotopy_class_planning
Activate homotopy class planning (Requires much more resources that simple planning, since multiple trajectories are optimized at once).
Definition: teb_config.h:171
geometry_msgs::Twist last_cmd_
Store the last control command generated in computeVelocityCommands()
bool free_goal_vel
Allow the robot&#39;s velocity to be nonzero (usally max_vel) for planning purposes.
Definition: teb_config.h:112
void pushBackVertex(const Eigen::Ref< const Eigen::Vector2d > &vertex)
Add a vertex to the polygon (edge-point)
Definition: obstacles.h:904
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:97
static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose &tf_vel)
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities...
double oscillation_v_eps
Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps ...
Definition: teb_config.h:207
unsigned int getSizeInCellsY() const
static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name)
Get a number from the given XmlRpcValue.
#define ROS_WARN_STREAM(args)
virtual std::string getName(const std::string &lookup_name)
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
double oscillation_filter_duration
Filter length/duration [sec] for the detection of oscillations.
Definition: teb_config.h:210
double & y()
Access the y-coordinate the pose.
Definition: pose_se2.h:170
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:57
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: pose_se2.h:182
void configureBackupModes(std::vector< geometry_msgs::PoseStamped > &transformed_plan, int &goal_idx)
PoseSE2 robot_pose_
Store current robot pose.
base_local_planner::OdometryHelperRos odom_helper_
Provides an interface to receive the current velocity from the robot.
void saturateVelocity(double &vx, double &vy, double &omega, double max_vel_x, double max_vel_y, double max_vel_theta, double max_vel_x_backwards) const
Saturate the translational and angular velocity to given limits.
double shrink_horizon_min_duration
Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected...
Definition: teb_config.h:205
costmap_2d::Costmap2D * costmap_
Pointer to the 2d costmap (obtained from the costmap ros wrapper)
Implements the actual abstract navigation stack routines of the teb_local_planner plugin...
bool costmap_converter_spin_thread
If true, the costmap converter invokes its callback queue in a different thread.
Definition: teb_config.h:130
unsigned int getSizeInCellsX() const
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
#define ROS_INFO_STREAM(args)
void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg)
Callback for custom obstacles that are not obtained from the costmap.
std::string frame_id_
static const unsigned char LETHAL_OBSTACLE
std::string robot_base_frame_
Used as the base frame id of the robot.
void transformPose(const std::string &target_frame, const geometry_msgs::PoseStamped &stamped_in, geometry_msgs::PoseStamped &stamped_out) const
Quaternion getRotation() const
double average_angles(const std::vector< double > &angles)
Return the average angle of an arbitrary number of given angles [rad].
Definition: misc.h:72
std::string costmap_converter_plugin
Define a plugin name of the costmap_converter package (costmap cells are converted to points/lines/po...
Definition: teb_config.h:129
bool getParam(const std::string &key, std::string &s) const
bool isOscillating() const
Check if the robot got stucked.
void validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist)
Validate current parameter values of the footprint for optimization, obstacle distance and the costma...
ros::Subscriber via_points_sub_
Subscriber for custom via-points received via a Path msg.
void updateObstacleContainerWithCostmap()
Update internal obstacle vector based on occupied costmap cells.
#define ROS_WARN_COND(cond,...)
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
#define ROS_INFO_COND(cond,...)
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
Definition: teb_config.h:76
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
TFSIMD_FORCE_INLINE const tfScalar & getX() const
static Time now()
double robot_inscribed_radius_
The radius of the inscribed circle of the robot (collision possible)
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > costmap_converter_
Store the current costmap_converter.
int costmap_converter_rate
The rate that defines how often the costmap_converter plugin processes the current costmap (the value...
Definition: teb_config.h:131
void setOdomTopic(std::string odom_topic)
double global_plan_prune_distance
Distance between robot and via_points of global plan which is used for pruning.
Definition: teb_config.h:81
PlannerInterfacePtr planner_
Instance of the underlying optimal planner class.
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
Definition: teb_config.h:95
std::string global_frame_
The frame in which the controller will run.
double oscillation_recovery_min_duration
Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected...
Definition: teb_config.h:209
double convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius=0) const
Convert translational and rotational velocities to a steering angle of a carlike robot.
ros::Time time_last_oscillation_
Store at which time stamp the last oscillation was detected.
double getResolution() const
Costmap2D * getCostmap()
bool hasParam(const std::string &key) const
ObstContainer obstacles_
Obstacle vector that should be considered during local trajectory optimization.
#define ROS_ERROR_STREAM(args)
double distance_points2d(const P1 &point1, const P2 &point2)
Calculate Euclidean distance between two 2D point datatypes.
Definition: misc.h:107
std::vector< geometry_msgs::Point > getRobotFootprint()
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the teb local planner is following.
ViaPointContainer via_points_
Container of via-points that should be considered during local trajectory optimization.
double oscillation_omega_eps
Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps...
Definition: teb_config.h:208
#define ROS_ERROR(...)
double wheelbase
The distance between the drive shaft and steering axle (only required for a carlike robot with &#39;cmd_a...
Definition: teb_config.h:102
double max_global_plan_lookahead_dist
Specify maximum length (cumulative Euclidean distances) of the subset of the global plan taken into a...
Definition: teb_config.h:80
geometry_msgs::Twist robot_vel_
Store current robot translational and angular velocity (vx, vy, omega)
bool oscillation_recovery
Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robo...
Definition: teb_config.h:206
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
boost::mutex & configMutex()
Return the internal config mutex.
Definition: teb_config.h:395
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:94
void reconfigureCB(TebLocalPlannerReconfigureConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)
def sign(number)
#define ROS_DEBUG(...)


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08