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 
41 #include <tf2_eigen/tf2_eigen.h>
43 
44 #include <boost/algorithm/string.hpp>
45 
46 // MBF return codes
47 #include <mbf_msgs/ExePathResult.h>
48 
49 // pluginlib macros
51 
52 #include "g2o/core/sparse_optimizer.h"
53 #include "g2o/core/block_solver.h"
54 #include "g2o/core/factory.h"
55 #include "g2o/core/optimization_algorithm_gauss_newton.h"
56 #include "g2o/core/optimization_algorithm_levenberg.h"
57 #include "g2o/solvers/csparse/linear_solver_csparse.h"
58 #include "g2o/solvers/cholmod/linear_solver_cholmod.h"
59 
60 
61 // register this planner both as a BaseLocalPlanner and as a MBF's CostmapController plugin
64 
65 namespace teb_local_planner
66 {
67 
68 
69 TebLocalPlannerROS::TebLocalPlannerROS() : costmap_ros_(NULL), tf_(NULL), costmap_model_(NULL),
70  costmap_converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"),
71  dynamic_recfg_(NULL), custom_via_points_active_(false), goal_reached_(false), no_infeasible_plans_(0),
72  last_preferred_rotdir_(RotType::none), initialized_(false)
73 {
74 }
75 
76 
78 {
79 }
80 
81 void TebLocalPlannerROS::reconfigureCB(TebLocalPlannerReconfigureConfig& config, uint32_t level)
82 {
84  ros::NodeHandle nh("~/" + name_);
85  // lock the config mutex externally
86  boost::mutex::scoped_lock lock(cfg_.configMutex());
87 
88  // create robot footprint/contour model for optimization
90  planner_->updateRobotModel(cfg_.robot_model);
91 }
92 
94 {
95  // check if the plugin is already initialized
96  if(!initialized_)
97  {
98  name_ = name;
99  // create Node Handle with name of plugin (as used in move_base for loading)
100  ros::NodeHandle nh("~/" + name);
101 
102  // get parameters of TebConfig via the nodehandle and override the default config
104 
105  // reserve some memory for obstacles
106  obstacles_.reserve(500);
107 
108  // create visualization instance
110 
111  // create robot footprint/contour model for optimization
113 
114  // create the planner instance
116  {
118  ROS_INFO("Parallel planning in distinctive topologies enabled.");
119  }
120  else
121  {
123  ROS_INFO("Parallel planning in distinctive topologies disabled.");
124  }
125 
126  // init other variables
127  tf_ = tf;
128  costmap_ros_ = costmap_ros;
129  costmap_ = costmap_ros_->getCostmap(); // locking should be done in MoveBase.
130 
131  costmap_model_ = boost::make_shared<base_local_planner::CostmapModel>(*costmap_);
132 
134  cfg_.map_frame = global_frame_; // TODO
136 
137  //Initialize a costmap to polygon converter
139  {
140  try
141  {
144  // replace '::' by '/' to convert the c++ namespace to a NodeHandle namespace
145  boost::replace_all(converter_name, "::", "/");
146  costmap_converter_->setOdomTopic(cfg_.odom_topic);
147  costmap_converter_->initialize(ros::NodeHandle(nh, "costmap_converter/" + converter_name));
148  costmap_converter_->setCostmap2D(costmap_);
149 
151  ROS_INFO_STREAM("Costmap conversion plugin " << cfg_.obstacles.costmap_converter_plugin << " loaded.");
152  }
154  {
155  ROS_WARN("The specified costmap converter plugin cannot be loaded. All occupied costmap cells are treaten as point obstacles. Error message: %s", ex.what());
156  costmap_converter_.reset();
157  }
158  }
159  else
160  ROS_INFO("No costmap conversion plugin specified. All occupied costmap cells are treaten as point obstacles.");
161 
162 
163  // Get footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices.
166 
167  // init the odom helper to receive the robot's velocity from odom messages
169 
170  // setup dynamic reconfigure
171  dynamic_recfg_ = boost::make_shared< dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig> >(nh);
172  dynamic_reconfigure::Server<TebLocalPlannerReconfigureConfig>::CallbackType cb = boost::bind(&TebLocalPlannerROS::reconfigureCB, this, _1, _2);
173  dynamic_recfg_->setCallback(cb);
174 
175  // validate optimization footprint and costmap footprint
177 
178  // setup callback for custom obstacles
179  custom_obst_sub_ = nh.subscribe("obstacles", 1, &TebLocalPlannerROS::customObstacleCB, this);
180 
181  // setup callback for custom via-points
182  via_points_sub_ = nh.subscribe("via_points", 1, &TebLocalPlannerROS::customViaPointsCB, this);
183 
184  // initialize failure detector
185  ros::NodeHandle nh_move_base("~");
186  double controller_frequency = 5;
187  nh_move_base.param("controller_frequency", controller_frequency, controller_frequency);
189 
190  // set initialized flag
191  initialized_ = true;
192 
193  ROS_DEBUG("teb_local_planner plugin initialized.");
194  }
195  else
196  {
197  ROS_WARN("teb_local_planner has already been initialized, doing nothing.");
198  }
199 }
200 
201 
202 
203 bool TebLocalPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
204 {
205  // check if plugin is initialized
206  if(!initialized_)
207  {
208  ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner");
209  return false;
210  }
211 
212  // store the global plan
213  global_plan_.clear();
214  global_plan_ = orig_global_plan;
215 
216  // we do not clear the local planner here, since setPlan is called frequently whenever the global planner updates the plan.
217  // the local planner checks whether it is required to reinitialize the trajectory or not within each velocity computation step.
218 
219  // reset goal_reached_ flag
220  goal_reached_ = false;
221 
222  return true;
223 }
224 
225 
227 {
228  std::string dummy_message;
229  geometry_msgs::PoseStamped dummy_pose;
230  geometry_msgs::TwistStamped dummy_velocity, cmd_vel_stamped;
231  uint32_t outcome = computeVelocityCommands(dummy_pose, dummy_velocity, cmd_vel_stamped, dummy_message);
232  cmd_vel = cmd_vel_stamped.twist;
233  return outcome == mbf_msgs::ExePathResult::SUCCESS;
234 }
235 
236 uint32_t TebLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseStamped& pose,
237  const geometry_msgs::TwistStamped& velocity,
238  geometry_msgs::TwistStamped &cmd_vel,
239  std::string &message)
240 {
241  // check if plugin initialized
242  if(!initialized_)
243  {
244  ROS_ERROR("teb_local_planner has not been initialized, please call initialize() before using this planner");
245  message = "teb_local_planner has not been initialized";
246  return mbf_msgs::ExePathResult::NOT_INITIALIZED;
247  }
248 
249  static uint32_t seq = 0;
250  cmd_vel.header.seq = seq++;
251  cmd_vel.header.stamp = ros::Time::now();
252  cmd_vel.header.frame_id = robot_base_frame_;
253  cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
254  goal_reached_ = false;
255 
256  // Get robot pose
257  geometry_msgs::PoseStamped robot_pose;
258  costmap_ros_->getRobotPose(robot_pose);
259  robot_pose_ = PoseSE2(robot_pose.pose);
260 
261  // Get robot velocity
262  geometry_msgs::PoseStamped robot_vel_tf;
263  odom_helper_.getRobotVel(robot_vel_tf);
264  robot_vel_.linear.x = robot_vel_tf.pose.position.x;
265  robot_vel_.linear.y = robot_vel_tf.pose.position.y;
266  robot_vel_.angular.z = tf2::getYaw(robot_vel_tf.pose.orientation);
267 
268  // prune global plan to cut off parts of the past (spatially before the robot)
270 
271  // Transform global plan to the frame of interest (w.r.t. the local costmap)
272  std::vector<geometry_msgs::PoseStamped> transformed_plan;
273  int goal_idx;
274  geometry_msgs::TransformStamped tf_plan_to_global;
276  transformed_plan, &goal_idx, &tf_plan_to_global))
277  {
278  ROS_WARN("Could not transform the global plan to the frame of the controller");
279  message = "Could not transform the global plan to the frame of the controller";
280  return mbf_msgs::ExePathResult::INTERNAL_ERROR;
281  }
282 
283  // update via-points container
286 
287  nav_msgs::Odometry base_odom;
288  odom_helper_.getOdom(base_odom);
289 
290  // check if global goal is reached
291  geometry_msgs::PoseStamped global_goal;
292  tf2::doTransform(global_plan_.back(), global_goal, tf_plan_to_global);
293  double dx = global_goal.pose.position.x - robot_pose_.x();
294  double dy = global_goal.pose.position.y - robot_pose_.y();
295  double delta_orient = g2o::normalize_theta( tf2::getYaw(global_goal.pose.orientation) - robot_pose_.theta() );
296  if(fabs(std::sqrt(dx*dx+dy*dy)) < cfg_.goal_tolerance.xy_goal_tolerance
297  && fabs(delta_orient) < cfg_.goal_tolerance.yaw_goal_tolerance
301  {
302  goal_reached_ = true;
303  return mbf_msgs::ExePathResult::SUCCESS;
304  }
305 
306  // check if we should enter any backup mode and apply settings
307  configureBackupModes(transformed_plan, goal_idx);
308 
309 
310  // Return false if the transformed global plan is empty
311  if (transformed_plan.empty())
312  {
313  ROS_WARN("Transformed plan is empty. Cannot determine a local plan.");
314  message = "Transformed plan is empty";
315  return mbf_msgs::ExePathResult::INVALID_PATH;
316  }
317 
318  // Get current goal point (last point of the transformed plan)
319  robot_goal_.x() = transformed_plan.back().pose.position.x;
320  robot_goal_.y() = transformed_plan.back().pose.position.y;
321  // Overwrite goal orientation if needed
323  {
324  robot_goal_.theta() = estimateLocalGoalOrientation(global_plan_, transformed_plan.back(), goal_idx, tf_plan_to_global);
325  // overwrite/update goal orientation of the transformed plan with the actual goal (enable using the plan as initialization)
326  tf2::Quaternion q;
327  q.setRPY(0, 0, robot_goal_.theta());
328  tf2::convert(q, transformed_plan.back().pose.orientation);
329  }
330  else
331  {
332  robot_goal_.theta() = tf2::getYaw(transformed_plan.back().pose.orientation);
333  }
334 
335  // overwrite/update start of the transformed plan with the actual robot position (allows using the plan as initial trajectory)
336  if (transformed_plan.size()==1) // plan only contains the goal
337  {
338  transformed_plan.insert(transformed_plan.begin(), geometry_msgs::PoseStamped()); // insert start (not yet initialized)
339  }
340  transformed_plan.front() = robot_pose; // update start
341 
342  // clear currently existing obstacles
343  obstacles_.clear();
344 
345  // Update obstacle container with costmap information or polygons provided by a costmap_converter plugin
346  if (costmap_converter_)
348  else
350 
351  // also consider custom obstacles (must be called after other updates, since the container is not cleared)
353 
354 
355  // Do not allow config changes during the following optimization step
356  boost::mutex::scoped_lock cfg_lock(cfg_.configMutex());
357 
358  // Now perform the actual planning
359 // bool success = planner_->plan(robot_pose_, robot_goal_, robot_vel_, cfg_.goal_tolerance.free_goal_vel); // straight line init
360  bool success = planner_->plan(transformed_plan, &robot_vel_, cfg_.goal_tolerance.free_goal_vel);
361  if (!success)
362  {
363  planner_->clearPlanner(); // force reinitialization for next time
364  ROS_WARN("teb_local_planner was not able to obtain a local plan for the current setting.");
365 
366  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
368  last_cmd_ = cmd_vel.twist;
369  message = "teb_local_planner was not able to obtain a local plan";
370  return mbf_msgs::ExePathResult::NO_VALID_CMD;
371  }
372 
373  // Check for divergence
374  if (planner_->hasDiverged())
375  {
376  cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
377 
378  // Reset everything to start again with the initialization of new trajectories.
379  planner_->clearPlanner();
380  ROS_WARN_THROTTLE(1.0, "TebLocalPlannerROS: the trajectory has diverged. Resetting planner...");
381 
382  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
384  last_cmd_ = cmd_vel.twist;
385  return mbf_msgs::ExePathResult::NO_VALID_CMD;
386  }
387 
388  // Check feasibility (but within the first few states only)
390  {
391  // Update footprint of the robot and minimum and maximum distance from the center of the robot to its footprint vertices.
394  }
395 
397  if (!feasible)
398  {
399  cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
400 
401  // now we reset everything to start again with the initialization of new trajectories.
402  planner_->clearPlanner();
403  ROS_WARN("TebLocalPlannerROS: trajectory is not feasible. Resetting planner...");
404 
405  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
407  last_cmd_ = cmd_vel.twist;
408  message = "teb_local_planner trajectory is not feasible";
409  return mbf_msgs::ExePathResult::NO_VALID_CMD;
410  }
411 
412  // Get the velocity command for this sampling interval
413  if (!planner_->getVelocityCommand(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z, cfg_.trajectory.control_look_ahead_poses))
414 
415  {
416  planner_->clearPlanner();
417  ROS_WARN("TebLocalPlannerROS: velocity command invalid. Resetting planner...");
418  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
420  last_cmd_ = cmd_vel.twist;
421  message = "teb_local_planner velocity command invalid";
422  return mbf_msgs::ExePathResult::NO_VALID_CMD;
423  }
424 
425  // Saturate velocity, if the optimization results violates the constraints (could be possible due to soft constraints).
426  saturateVelocity(cmd_vel.twist.linear.x, cmd_vel.twist.linear.y, cmd_vel.twist.angular.z,
429 
430  // convert rot-vel to steering angle if desired (carlike robot).
431  // The min_turning_radius is allowed to be slighly smaller since it is a soft-constraint
432  // and opposed to the other constraints not affected by penalty_epsilon. The user might add a safety margin to the parameter itself.
434  {
435  cmd_vel.twist.angular.z = convertTransRotVelToSteeringAngle(cmd_vel.twist.linear.x, cmd_vel.twist.angular.z,
437  if (!std::isfinite(cmd_vel.twist.angular.z))
438  {
439  cmd_vel.twist.linear.x = cmd_vel.twist.linear.y = cmd_vel.twist.angular.z = 0;
440  last_cmd_ = cmd_vel.twist;
441  planner_->clearPlanner();
442  ROS_WARN("TebLocalPlannerROS: Resulting steering angle is not finite. Resetting planner...");
443  ++no_infeasible_plans_; // increase number of infeasible solutions in a row
445  message = "teb_local_planner steering angle is not finite";
446  return mbf_msgs::ExePathResult::NO_VALID_CMD;
447  }
448  }
449 
450  // a feasible solution should be found, reset counter
452 
453  // store last command (for recovery analysis etc.)
454  last_cmd_ = cmd_vel.twist;
455 
456  // Now visualize everything
457  planner_->visualize();
458  visualization_->publishObstacles(obstacles_, costmap_->getResolution());
459  visualization_->publishViaPoints(via_points_);
460  visualization_->publishGlobalPlan(global_plan_);
461  return mbf_msgs::ExePathResult::SUCCESS;
462 }
463 
464 
466 {
467  if (goal_reached_)
468  {
469  ROS_INFO("GOAL Reached!");
470  planner_->clearPlanner();
471  return true;
472  }
473  return false;
474 }
475 
476 
477 
479 {
480  // Add costmap obstacles if desired
482  {
483  Eigen::Vector2d robot_orient = robot_pose_.orientationUnitVec();
484 
485  for (unsigned int i=0; i<costmap_->getSizeInCellsX()-1; ++i)
486  {
487  for (unsigned int j=0; j<costmap_->getSizeInCellsY()-1; ++j)
488  {
490  {
491  Eigen::Vector2d obs;
492  costmap_->mapToWorld(i,j,obs.coeffRef(0), obs.coeffRef(1));
493 
494  // check if obstacle is interesting (e.g. not far behind the robot)
495  Eigen::Vector2d obs_dir = obs-robot_pose_.position();
496  if ( obs_dir.dot(robot_orient) < 0 && obs_dir.norm() > cfg_.obstacles.costmap_obstacles_behind_robot_dist )
497  continue;
498 
499  obstacles_.push_back(ObstaclePtr(new PointObstacle(obs)));
500  }
501  }
502  }
503  }
504 }
505 
507 {
508  if (!costmap_converter_)
509  return;
510 
511  //Get obstacles from costmap converter
513  if (!obstacles)
514  return;
515 
516  for (std::size_t i=0; i<obstacles->obstacles.size(); ++i)
517  {
518  const costmap_converter::ObstacleMsg* obstacle = &obstacles->obstacles.at(i);
519  const geometry_msgs::Polygon* polygon = &obstacle->polygon;
520 
521  if (polygon->points.size()==1 && obstacle->radius > 0) // Circle
522  {
523  obstacles_.push_back(ObstaclePtr(new CircularObstacle(polygon->points[0].x, polygon->points[0].y, obstacle->radius)));
524  }
525  else if (polygon->points.size()==1) // Point
526  {
527  obstacles_.push_back(ObstaclePtr(new PointObstacle(polygon->points[0].x, polygon->points[0].y)));
528  }
529  else if (polygon->points.size()==2) // Line
530  {
531  obstacles_.push_back(ObstaclePtr(new LineObstacle(polygon->points[0].x, polygon->points[0].y,
532  polygon->points[1].x, polygon->points[1].y )));
533  }
534  else if (polygon->points.size()>2) // Real polygon
535  {
536  PolygonObstacle* polyobst = new PolygonObstacle;
537  for (std::size_t j=0; j<polygon->points.size(); ++j)
538  {
539  polyobst->pushBackVertex(polygon->points[j].x, polygon->points[j].y);
540  }
541  polyobst->finalizePolygon();
542  obstacles_.push_back(ObstaclePtr(polyobst));
543  }
544 
545  // Set velocity, if obstacle is moving
546  if(!obstacles_.empty())
547  obstacles_.back()->setCentroidVelocity(obstacles->obstacles[i].velocities, obstacles->obstacles[i].orientation);
548  }
549 }
550 
551 
553 {
554  // Add custom obstacles obtained via message
555  boost::mutex::scoped_lock l(custom_obst_mutex_);
556 
557  if (!custom_obstacle_msg_.obstacles.empty())
558  {
559  // We only use the global header to specify the obstacle coordinate system instead of individual ones
560  Eigen::Affine3d obstacle_to_map_eig;
561  try
562  {
563  geometry_msgs::TransformStamped obstacle_to_map = tf_->lookupTransform(global_frame_, ros::Time(0),
564  custom_obstacle_msg_.header.frame_id, ros::Time(0),
566  obstacle_to_map_eig = tf2::transformToEigen(obstacle_to_map);
567  }
568  catch (tf::TransformException ex)
569  {
570  ROS_ERROR("%s",ex.what());
571  obstacle_to_map_eig.setIdentity();
572  }
573 
574  for (size_t i=0; i<custom_obstacle_msg_.obstacles.size(); ++i)
575  {
576  if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 1 && custom_obstacle_msg_.obstacles.at(i).radius > 0 ) // circle
577  {
578  Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x,
579  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y,
580  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z );
581  obstacles_.push_back(ObstaclePtr(new CircularObstacle( (obstacle_to_map_eig * pos).head(2), custom_obstacle_msg_.obstacles.at(i).radius)));
582  }
583  else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 1 ) // point
584  {
585  Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x,
586  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y,
587  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z );
588  obstacles_.push_back(ObstaclePtr(new PointObstacle( (obstacle_to_map_eig * pos).head(2) )));
589  }
590  else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.size() == 2 ) // line
591  {
592  Eigen::Vector3d line_start( custom_obstacle_msg_.obstacles.at(i).polygon.points.front().x,
593  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().y,
594  custom_obstacle_msg_.obstacles.at(i).polygon.points.front().z );
595  Eigen::Vector3d line_end( custom_obstacle_msg_.obstacles.at(i).polygon.points.back().x,
596  custom_obstacle_msg_.obstacles.at(i).polygon.points.back().y,
597  custom_obstacle_msg_.obstacles.at(i).polygon.points.back().z );
598  obstacles_.push_back(ObstaclePtr(new LineObstacle( (obstacle_to_map_eig * line_start).head(2),
599  (obstacle_to_map_eig * line_end).head(2) )));
600  }
601  else if (custom_obstacle_msg_.obstacles.at(i).polygon.points.empty())
602  {
603  ROS_WARN("Invalid custom obstacle received. List of polygon vertices is empty. Skipping...");
604  continue;
605  }
606  else // polygon
607  {
608  PolygonObstacle* polyobst = new PolygonObstacle;
609  for (size_t j=0; j<custom_obstacle_msg_.obstacles.at(i).polygon.points.size(); ++j)
610  {
611  Eigen::Vector3d pos( custom_obstacle_msg_.obstacles.at(i).polygon.points[j].x,
612  custom_obstacle_msg_.obstacles.at(i).polygon.points[j].y,
613  custom_obstacle_msg_.obstacles.at(i).polygon.points[j].z );
614  polyobst->pushBackVertex( (obstacle_to_map_eig * pos).head(2) );
615  }
616  polyobst->finalizePolygon();
617  obstacles_.push_back(ObstaclePtr(polyobst));
618  }
619 
620  // Set velocity, if obstacle is moving
621  if(!obstacles_.empty())
622  obstacles_.back()->setCentroidVelocity(custom_obstacle_msg_.obstacles[i].velocities, custom_obstacle_msg_.obstacles[i].orientation);
623  }
624  }
625 }
626 
627 void TebLocalPlannerROS::updateViaPointsContainer(const std::vector<geometry_msgs::PoseStamped>& transformed_plan, double min_separation)
628 {
629  via_points_.clear();
630 
631  if (min_separation<=0)
632  return;
633 
634  std::size_t prev_idx = 0;
635  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]
636  {
637  // check separation to the previous via-point inserted
638  if (distance_points2d( transformed_plan[prev_idx].pose.position, transformed_plan[i].pose.position ) < min_separation)
639  continue;
640 
641  // add via-point
642  via_points_.push_back( Eigen::Vector2d( transformed_plan[i].pose.position.x, transformed_plan[i].pose.position.y ) );
643  prev_idx = i;
644  }
645 
646 }
647 
648 Eigen::Vector2d TebLocalPlannerROS::tfPoseToEigenVector2dTransRot(const tf::Pose& tf_vel)
649 {
650  Eigen::Vector2d vel;
651  vel.coeffRef(0) = std::sqrt( tf_vel.getOrigin().getX() * tf_vel.getOrigin().getX() + tf_vel.getOrigin().getY() * tf_vel.getOrigin().getY() );
652  vel.coeffRef(1) = tf::getYaw(tf_vel.getRotation());
653  return vel;
654 }
655 
656 
657 bool TebLocalPlannerROS::pruneGlobalPlan(const tf2_ros::Buffer& tf, const geometry_msgs::PoseStamped& global_pose, std::vector<geometry_msgs::PoseStamped>& global_plan, double dist_behind_robot)
658 {
659  if (global_plan.empty())
660  return true;
661 
662  try
663  {
664  // transform robot pose into the plan frame (we do not wait here, since pruning not crucial, if missed a few times)
665  geometry_msgs::TransformStamped global_to_plan_transform = tf.lookupTransform(global_plan.front().header.frame_id, global_pose.header.frame_id, ros::Time(0));
666  geometry_msgs::PoseStamped robot;
667  tf2::doTransform(global_pose, robot, global_to_plan_transform);
668 
669  double dist_thresh_sq = dist_behind_robot*dist_behind_robot;
670 
671  // iterate plan until a pose close the robot is found
672  std::vector<geometry_msgs::PoseStamped>::iterator it = global_plan.begin();
673  std::vector<geometry_msgs::PoseStamped>::iterator erase_end = it;
674  while (it != global_plan.end())
675  {
676  double dx = robot.pose.position.x - it->pose.position.x;
677  double dy = robot.pose.position.y - it->pose.position.y;
678  double dist_sq = dx * dx + dy * dy;
679  if (dist_sq < dist_thresh_sq)
680  {
681  erase_end = it;
682  break;
683  }
684  ++it;
685  }
686  if (erase_end == global_plan.end())
687  return false;
688 
689  if (erase_end != global_plan.begin())
690  global_plan.erase(global_plan.begin(), erase_end);
691  }
692  catch (const tf::TransformException& ex)
693  {
694  ROS_DEBUG("Cannot prune path since no transform is available: %s\n", ex.what());
695  return false;
696  }
697  return true;
698 }
699 
700 
701 bool TebLocalPlannerROS::transformGlobalPlan(const tf2_ros::Buffer& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
702  const geometry_msgs::PoseStamped& global_pose, const costmap_2d::Costmap2D& costmap, const std::string& global_frame, double max_plan_length,
703  std::vector<geometry_msgs::PoseStamped>& transformed_plan, int* current_goal_idx, geometry_msgs::TransformStamped* tf_plan_to_global) const
704 {
705  // this method is a slightly modified version of base_local_planner/goal_functions.h
706 
707  const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
708 
709  transformed_plan.clear();
710 
711  try
712  {
713  if (global_plan.empty())
714  {
715  ROS_ERROR("Received plan with zero length");
716  *current_goal_idx = 0;
717  return false;
718  }
719 
720  // get plan_to_global_transform from plan frame to global_frame
721  geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, ros::Time(), plan_pose.header.frame_id, plan_pose.header.stamp,
722  plan_pose.header.frame_id, ros::Duration(cfg_.robot.transform_tolerance));
723 
724  //let's get the pose of the robot in the frame of the plan
725  geometry_msgs::PoseStamped robot_pose;
726  tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);
727 
728  //we'll discard points on the plan that are outside the local costmap
729  double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0,
730  costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
731  dist_threshold *= 0.85; // just consider 85% of the costmap size to better incorporate point obstacle that are
732  // located on the border of the local costmap
733 
734 
735  int i = 0;
736  double sq_dist_threshold = dist_threshold * dist_threshold;
737  double sq_dist = 1e10;
738 
739  //we need to loop to a point on the plan that is within a certain distance of the robot
740  bool robot_reached = false;
741  for(int j=0; j < (int)global_plan.size(); ++j)
742  {
743  double x_diff = robot_pose.pose.position.x - global_plan[j].pose.position.x;
744  double y_diff = robot_pose.pose.position.y - global_plan[j].pose.position.y;
745  double new_sq_dist = x_diff * x_diff + y_diff * y_diff;
746 
747  if (robot_reached && new_sq_dist > sq_dist)
748  break;
749 
750  if (new_sq_dist < sq_dist) // find closest distance
751  {
752  sq_dist = new_sq_dist;
753  i = j;
754  if (sq_dist < 0.05) // 2.5 cm to the robot; take the immediate local minima; if it's not the global
755  robot_reached = true; // minima, probably means that there's a loop in the path, and so we prefer this
756  }
757  }
758 
759  geometry_msgs::PoseStamped newer_pose;
760 
761  double plan_length = 0; // check cumulative Euclidean distance along the plan
762 
763  //now we'll transform until points are outside of our distance threshold
764  while(i < (int)global_plan.size() && sq_dist <= sq_dist_threshold && (max_plan_length<=0 || plan_length <= max_plan_length))
765  {
766  const geometry_msgs::PoseStamped& pose = global_plan[i];
767  tf2::doTransform(pose, newer_pose, plan_to_global_transform);
768 
769  transformed_plan.push_back(newer_pose);
770 
771  double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
772  double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
773  sq_dist = x_diff * x_diff + y_diff * y_diff;
774 
775  // caclulate distance to previous pose
776  if (i>0 && max_plan_length>0)
777  plan_length += distance_points2d(global_plan[i-1].pose.position, global_plan[i].pose.position);
778 
779  ++i;
780  }
781 
782  // if we are really close to the goal (<sq_dist_threshold) and the goal is not yet reached (e.g. orientation error >>0)
783  // the resulting transformed plan can be empty. In that case we explicitly inject the global goal.
784  if (transformed_plan.empty())
785  {
786  tf2::doTransform(global_plan.back(), newer_pose, plan_to_global_transform);
787 
788  transformed_plan.push_back(newer_pose);
789 
790  // Return the index of the current goal point (inside the distance threshold)
791  if (current_goal_idx) *current_goal_idx = int(global_plan.size())-1;
792  }
793  else
794  {
795  // Return the index of the current goal point (inside the distance threshold)
796  if (current_goal_idx) *current_goal_idx = i-1; // subtract 1, since i was increased once before leaving the loop
797  }
798 
799  // Return the transformation from the global plan to the global planning frame if desired
800  if (tf_plan_to_global) *tf_plan_to_global = plan_to_global_transform;
801  }
802  catch(tf::LookupException& ex)
803  {
804  ROS_ERROR("No Transform available Error: %s\n", ex.what());
805  return false;
806  }
807  catch(tf::ConnectivityException& ex)
808  {
809  ROS_ERROR("Connectivity Error: %s\n", ex.what());
810  return false;
811  }
812  catch(tf::ExtrapolationException& ex)
813  {
814  ROS_ERROR("Extrapolation Error: %s\n", ex.what());
815  if (global_plan.size() > 0)
816  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());
817 
818  return false;
819  }
820 
821  return true;
822 }
823 
824 
825 
826 
827 double TebLocalPlannerROS::estimateLocalGoalOrientation(const std::vector<geometry_msgs::PoseStamped>& global_plan, const geometry_msgs::PoseStamped& local_goal,
828  int current_goal_idx, const geometry_msgs::TransformStamped& tf_plan_to_global, int moving_average_length) const
829 {
830  int n = (int)global_plan.size();
831 
832  // check if we are near the global goal already
833  if (current_goal_idx > n-moving_average_length-2)
834  {
835  if (current_goal_idx >= n-1) // we've exactly reached the goal
836  {
837  return tf2::getYaw(local_goal.pose.orientation);
838  }
839  else
840  {
841  tf2::Quaternion global_orientation;
842  tf2::convert(global_plan.back().pose.orientation, global_orientation);
843  tf2::Quaternion rotation;
844  tf2::convert(tf_plan_to_global.transform.rotation, rotation);
845  // TODO(roesmann): avoid conversion to tf2::Quaternion
846  return tf2::getYaw(rotation * global_orientation);
847  }
848  }
849 
850  // reduce number of poses taken into account if the desired number of poses is not available
851  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
852 
853  std::vector<double> candidates;
854  geometry_msgs::PoseStamped tf_pose_k = local_goal;
855  geometry_msgs::PoseStamped tf_pose_kp1;
856 
857  int range_end = current_goal_idx + moving_average_length;
858  for (int i = current_goal_idx; i < range_end; ++i)
859  {
860  // Transform pose of the global plan to the planning frame
861  tf2::doTransform(global_plan.at(i+1), tf_pose_kp1, tf_plan_to_global);
862 
863  // calculate yaw angle
864  candidates.push_back( std::atan2(tf_pose_kp1.pose.position.y - tf_pose_k.pose.position.y,
865  tf_pose_kp1.pose.position.x - tf_pose_k.pose.position.x ) );
866 
867  if (i<range_end-1)
868  tf_pose_k = tf_pose_kp1;
869  }
870  return average_angles(candidates);
871 }
872 
873 
874 void TebLocalPlannerROS::saturateVelocity(double& vx, double& vy, double& omega, double max_vel_x, double max_vel_y, double max_vel_trans, double max_vel_theta,
875  double max_vel_x_backwards) const
876 {
877  double ratio_x = 1, ratio_omega = 1, ratio_y = 1;
878  // Limit translational velocity for forward driving
879  if (vx > max_vel_x)
880  ratio_x = max_vel_x / vx;
881 
882  // limit strafing velocity
883  if (vy > max_vel_y || vy < -max_vel_y)
884  ratio_y = std::abs(max_vel_y / vy);
885 
886  // Limit angular velocity
887  if (omega > max_vel_theta || omega < -max_vel_theta)
888  ratio_omega = std::abs(max_vel_theta / omega);
889 
890  // Limit backwards velocity
891  if (max_vel_x_backwards<=0)
892  {
893  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.");
894  }
895  else if (vx < -max_vel_x_backwards)
896  ratio_x = - max_vel_x_backwards / vx;
897 
899  {
900  double ratio = std::min(std::min(ratio_x, ratio_y), ratio_omega);
901  vx *= ratio;
902  vy *= ratio;
903  omega *= ratio;
904  }
905  else
906  {
907  vx *= ratio_x;
908  vy *= ratio_y;
909  omega *= ratio_omega;
910  }
911 
912  double vel_linear = std::hypot(vx, vy);
913  if (vel_linear > max_vel_trans)
914  {
915  double max_vel_trans_ratio = max_vel_trans / vel_linear;
916  vx *= max_vel_trans_ratio;
917  vy *= max_vel_trans_ratio;
918  }
919 }
920 
921 
922 double TebLocalPlannerROS::convertTransRotVelToSteeringAngle(double v, double omega, double wheelbase, double min_turning_radius) const
923 {
924  if (omega==0 || v==0)
925  return 0;
926 
927  double radius = v/omega;
928 
929  if (fabs(radius) < min_turning_radius)
930  radius = double(g2o::sign(radius)) * min_turning_radius;
931 
932  return std::atan(wheelbase / radius);
933 }
934 
935 
936 void TebLocalPlannerROS::validateFootprints(double opt_inscribed_radius, double costmap_inscribed_radius, double min_obst_dist)
937 {
938  ROS_WARN_COND(opt_inscribed_radius + min_obst_dist < costmap_inscribed_radius,
939  "The inscribed radius of the footprint specified for TEB optimization (%f) + min_obstacle_dist (%f) are smaller "
940  "than the inscribed radius of the robot's footprint in the costmap parameters (%f, including 'footprint_padding'). "
941  "Infeasible optimziation results might occur frequently!", opt_inscribed_radius, min_obst_dist, costmap_inscribed_radius);
942 }
943 
944 
945 
946 void TebLocalPlannerROS::configureBackupModes(std::vector<geometry_msgs::PoseStamped>& transformed_plan, int& goal_idx)
947 {
948  ros::Time current_time = ros::Time::now();
949 
950  // reduced horizon backup mode
952  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)
953  (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
954  {
955  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);
956 
957 
958  // Shorten horizon if requested
959  // reduce to 50 percent:
960  int horizon_reduction = goal_idx/2;
961 
962  if (no_infeasible_plans_ > 9)
963  {
964  ROS_INFO_COND(no_infeasible_plans_==10, "Infeasible trajectory detected 10 times in a row: further reducing horizon...");
965  horizon_reduction /= 2;
966  }
967 
968  // we have a small overhead here, since we already transformed 50% more of the trajectory.
969  // But that's ok for now, since we do not need to make transformGlobalPlan more complex
970  // and a reduced horizon should occur just rarely.
971  int new_goal_idx_transformed_plan = int(transformed_plan.size()) - horizon_reduction - 1;
972  goal_idx -= horizon_reduction;
973  if (new_goal_idx_transformed_plan>0 && goal_idx >= 0)
974  transformed_plan.erase(transformed_plan.begin()+new_goal_idx_transformed_plan, transformed_plan.end());
975  else
976  goal_idx += horizon_reduction; // this should not happen, but safety first ;-)
977  }
978 
979 
980  // detect and resolve oscillations
982  {
983  double max_vel_theta;
984  double max_vel_current = last_cmd_.linear.x >= 0 ? cfg_.robot.max_vel_x : cfg_.robot.max_vel_x_backwards;
985  if (cfg_.robot.min_turning_radius!=0 && max_vel_current>0)
986  max_vel_theta = std::max( max_vel_current/std::abs(cfg_.robot.min_turning_radius), cfg_.robot.max_vel_theta );
987  else
988  max_vel_theta = cfg_.robot.max_vel_theta;
989 
992 
993  bool oscillating = failure_detector_.isOscillating();
994  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
995 
996  if (oscillating)
997  {
998  if (!recently_oscillated)
999  {
1000  // save current turning direction
1001  if (robot_vel_.angular.z > 0)
1003  else
1005  ROS_WARN("TebLocalPlannerROS: possible oscillation (of the robot or its local plan) detected. Activating recovery strategy (prefer current turning direction during optimization).");
1006  }
1008  planner_->setPreferredTurningDir(last_preferred_rotdir_);
1009  }
1010  else if (!recently_oscillated && last_preferred_rotdir_ != RotType::none) // clear recovery behavior
1011  {
1013  planner_->setPreferredTurningDir(last_preferred_rotdir_);
1014  ROS_INFO("TebLocalPlannerROS: oscillation recovery disabled/expired.");
1015  }
1016  }
1017 
1018 }
1019 
1020 void TebLocalPlannerROS::customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr& obst_msg)
1021 {
1022  boost::mutex::scoped_lock l(custom_obst_mutex_);
1023  custom_obstacle_msg_ = *obst_msg;
1024 }
1025 
1026 void TebLocalPlannerROS::customViaPointsCB(const nav_msgs::Path::ConstPtr& via_points_msg)
1027 {
1028  ROS_INFO_ONCE("Via-points received. This message is printed once.");
1030  {
1031  ROS_WARN("Via-points are already obtained from the global plan (global_plan_viapoint_sep>0)."
1032  "Ignoring custom via-points.");
1033  custom_via_points_active_ = false;
1034  return;
1035  }
1036 
1037  boost::mutex::scoped_lock l(via_point_mutex_);
1038  via_points_.clear();
1039  for (const geometry_msgs::PoseStamped& pose : via_points_msg->poses)
1040  {
1041  via_points_.emplace_back(pose.pose.position.x, pose.pose.position.y);
1042  }
1044 }
1045 
1047 {
1048  std::string model_name;
1049  if (!nh.getParam("footprint_model/type", model_name))
1050  {
1051  ROS_INFO("No robot footprint model specified for trajectory optimization. Using point-shaped model.");
1052  return boost::make_shared<PointRobotFootprint>();
1053  }
1054 
1055  // point
1056  if (model_name.compare("point") == 0)
1057  {
1058  ROS_INFO("Footprint model 'point' loaded for trajectory optimization.");
1059  return boost::make_shared<PointRobotFootprint>(config.obstacles.min_obstacle_dist);
1060  }
1061 
1062  // circular
1063  if (model_name.compare("circular") == 0)
1064  {
1065  // get radius
1066  double radius;
1067  if (!nh.getParam("footprint_model/radius", radius))
1068  {
1069  ROS_ERROR_STREAM("Footprint model 'circular' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1070  << "/footprint_model/radius' does not exist. Using point-model instead.");
1071  return boost::make_shared<PointRobotFootprint>();
1072  }
1073  ROS_INFO_STREAM("Footprint model 'circular' (radius: " << radius <<"m) loaded for trajectory optimization.");
1074  return boost::make_shared<CircularRobotFootprint>(radius);
1075  }
1076 
1077  // line
1078  if (model_name.compare("line") == 0)
1079  {
1080  // check parameters
1081  if (!nh.hasParam("footprint_model/line_start") || !nh.hasParam("footprint_model/line_end"))
1082  {
1083  ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1084  << "/footprint_model/line_start' and/or '.../line_end' do not exist. Using point-model instead.");
1085  return boost::make_shared<PointRobotFootprint>();
1086  }
1087  // get line coordinates
1088  std::vector<double> line_start, line_end;
1089  nh.getParam("footprint_model/line_start", line_start);
1090  nh.getParam("footprint_model/line_end", line_end);
1091  if (line_start.size() != 2 || line_end.size() != 2)
1092  {
1093  ROS_ERROR_STREAM("Footprint model 'line' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1094  << "/footprint_model/line_start' and/or '.../line_end' do not contain x and y coordinates (2D). Using point-model instead.");
1095  return boost::make_shared<PointRobotFootprint>();
1096  }
1097 
1098  ROS_INFO_STREAM("Footprint model 'line' (line_start: [" << line_start[0] << "," << line_start[1] <<"]m, line_end: ["
1099  << line_end[0] << "," << line_end[1] << "]m) loaded for trajectory optimization.");
1100  return boost::make_shared<LineRobotFootprint>(Eigen::Map<const Eigen::Vector2d>(line_start.data()), Eigen::Map<const Eigen::Vector2d>(line_end.data()), config.obstacles.min_obstacle_dist);
1101  }
1102 
1103  // two circles
1104  if (model_name.compare("two_circles") == 0)
1105  {
1106  // check parameters
1107  if (!nh.hasParam("footprint_model/front_offset") || !nh.hasParam("footprint_model/front_radius")
1108  || !nh.hasParam("footprint_model/rear_offset") || !nh.hasParam("footprint_model/rear_radius"))
1109  {
1110  ROS_ERROR_STREAM("Footprint model 'two_circles' cannot be loaded for trajectory optimization, since params '" << nh.getNamespace()
1111  << "/footprint_model/front_offset', '.../front_radius', '.../rear_offset' and '.../rear_radius' do not exist. Using point-model instead.");
1112  return boost::make_shared<PointRobotFootprint>();
1113  }
1114  double front_offset, front_radius, rear_offset, rear_radius;
1115  nh.getParam("footprint_model/front_offset", front_offset);
1116  nh.getParam("footprint_model/front_radius", front_radius);
1117  nh.getParam("footprint_model/rear_offset", rear_offset);
1118  nh.getParam("footprint_model/rear_radius", rear_radius);
1119  ROS_INFO_STREAM("Footprint model 'two_circles' (front_offset: " << front_offset <<"m, front_radius: " << front_radius
1120  << "m, rear_offset: " << rear_offset << "m, rear_radius: " << rear_radius << "m) loaded for trajectory optimization.");
1121  return boost::make_shared<TwoCirclesRobotFootprint>(front_offset, front_radius, rear_offset, rear_radius);
1122  }
1123 
1124  // polygon
1125  if (model_name.compare("polygon") == 0)
1126  {
1127 
1128  // check parameters
1129  XmlRpc::XmlRpcValue footprint_xmlrpc;
1130  if (!nh.getParam("footprint_model/vertices", footprint_xmlrpc) )
1131  {
1132  ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1133  << "/footprint_model/vertices' does not exist. Using point-model instead.");
1134  return boost::make_shared<PointRobotFootprint>();
1135  }
1136  // get vertices
1137  if (footprint_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray)
1138  {
1139  try
1140  {
1141  Point2dContainer polygon = makeFootprintFromXMLRPC(footprint_xmlrpc, "/footprint_model/vertices");
1142  ROS_INFO_STREAM("Footprint model 'polygon' loaded for trajectory optimization.");
1143  return boost::make_shared<PolygonRobotFootprint>(polygon);
1144  }
1145  catch(const std::exception& ex)
1146  {
1147  ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization: " << ex.what() << ". Using point-model instead.");
1148  return boost::make_shared<PointRobotFootprint>();
1149  }
1150  }
1151  else
1152  {
1153  ROS_ERROR_STREAM("Footprint model 'polygon' cannot be loaded for trajectory optimization, since param '" << nh.getNamespace()
1154  << "/footprint_model/vertices' does not define an array of coordinates. Using point-model instead.");
1155  return boost::make_shared<PointRobotFootprint>();
1156  }
1157 
1158  }
1159 
1160  // otherwise
1161  ROS_WARN_STREAM("Unknown robot footprint model specified with parameter '" << nh.getNamespace() << "/footprint_model/type'. Using point model instead.");
1162  return boost::make_shared<PointRobotFootprint>();
1163 }
1164 
1165 
1166 
1167 
1168 Point2dContainer TebLocalPlannerROS::makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue& footprint_xmlrpc, const std::string& full_param_name)
1169 {
1170  // Make sure we have an array of at least 3 elements.
1171  if (footprint_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray ||
1172  footprint_xmlrpc.size() < 3)
1173  {
1174  ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s",
1175  full_param_name.c_str(), std::string(footprint_xmlrpc).c_str());
1176  throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least "
1177  "3 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]");
1178  }
1179 
1180  Point2dContainer footprint;
1181  Eigen::Vector2d pt;
1182 
1183  for (int i = 0; i < footprint_xmlrpc.size(); ++i)
1184  {
1185  // Make sure each element of the list is an array of size 2. (x and y coordinates)
1186  XmlRpc::XmlRpcValue point = footprint_xmlrpc[ i ];
1187  if (point.getType() != XmlRpc::XmlRpcValue::TypeArray ||
1188  point.size() != 2)
1189  {
1190  ROS_FATAL("The footprint (parameter %s) must be specified as list of lists on the parameter server eg: "
1191  "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.",
1192  full_param_name.c_str());
1193  throw std::runtime_error("The footprint must be specified as list of lists on the parameter server eg: "
1194  "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form");
1195  }
1196 
1197  pt.x() = getNumberFromXMLRPC(point[ 0 ], full_param_name);
1198  pt.y() = getNumberFromXMLRPC(point[ 1 ], full_param_name);
1199 
1200  footprint.push_back(pt);
1201  }
1202  return footprint;
1203 }
1205 double TebLocalPlannerROS::getNumberFromXMLRPC(XmlRpc::XmlRpcValue& value, const std::string& full_param_name)
1206 {
1207  // Make sure that the value we're looking at is either a double or an int.
1208  if (value.getType() != XmlRpc::XmlRpcValue::TypeInt &&
1210  {
1211  std::string& value_string = value;
1212  ROS_FATAL("Values in the footprint specification (param %s) must be numbers. Found value %s.",
1213  full_param_name.c_str(), value_string.c_str());
1214  throw std::runtime_error("Values in the footprint specification must be numbers");
1215  }
1216  return value.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(value) : (double)(value);
1217 }
1218 
1219 } // end namespace teb_local_planner
1220 
1221 
mbf_costmap_core::CostmapController
base_local_planner::OdometryHelperRos::setOdomTopic
void setOdomTopic(std::string odom_topic)
teb_local_planner::TebLocalPlannerROS::updateObstacleContainerWithCostmap
void updateObstacleContainerWithCostmap()
Update internal obstacle vector based on occupied costmap cells.
Definition: teb_local_planner_ros.cpp:514
XmlRpc::XmlRpcValue::size
int size() const
tf::Transform::getRotation
Quaternion getRotation() const
teb_local_planner::TebConfig::Robot::transform_tolerance
double transform_tolerance
Definition: teb_config.h:112
teb_local_planner::PoseSE2::x
double & x()
Access the x-coordinate the pose.
Definition: pose_se2.h:194
teb_local_planner::TebLocalPlannerROS::custom_via_points_active_
bool custom_via_points_active_
Keep track whether valid via-points have been received from via_points_sub_.
Definition: teb_local_planner_ros.h:461
tf2::convert
void convert(const A &a, B &b)
teb_local_planner::TebLocalPlannerROS::computeVelocityCommands
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Definition: teb_local_planner_ros.cpp:262
teb_local_planner::TebLocalPlannerROS::updateViaPointsContainer
void updateViaPointsContainer(const std::vector< geometry_msgs::PoseStamped > &transformed_plan, double min_separation)
Update internal via-point container based on the current reference plan.
Definition: teb_local_planner_ros.cpp:663
teb_local_planner::TebLocalPlannerROS::via_points_
ViaPointContainer via_points_
Container of via-points that should be considered during local trajectory optimization.
Definition: teb_local_planner_ros.h:442
teb_local_planner::RobotFootprintModelPtr
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
Abbrev. for shared obstacle pointers.
Definition: robot_footprint_model.h:156
teb_local_planner::TebConfig::Robot::max_vel_y
double max_vel_y
Maximum strafing velocity of the robot (should be zero for non-holonomic robots!)
Definition: teb_config.h:101
cmd_vel_to_ackermann_drive.Twist
Twist
Definition: cmd_vel_to_ackermann_drive.py:56
teb_local_planner::TebLocalPlannerROS::custom_obstacle_msg_
costmap_converter::ObstacleArrayMsg custom_obstacle_msg_
Copy of the most recent obstacle message.
Definition: teb_local_planner_ros.h:458
teb_local_planner::TebConfig::Robot::max_vel_trans
double max_vel_trans
Maximum translational velocity of the robot for omni robots, which is different from max_vel_x.
Definition: teb_config.h:102
teb_local_planner::TebLocalPlannerROS::robot_pose_
PoseSE2 robot_pose_
Store current robot pose.
Definition: teb_local_planner_ros.h:464
teb_local_planner::TebLocalPlannerROS::updateObstacleContainerWithCostmapConverter
void updateObstacleContainerWithCostmapConverter()
Update internal obstacle vector based on polygons provided by a costmap_converter plugin.
Definition: teb_local_planner_ros.cpp:542
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
teb_local_planner::FailureDetector::update
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.
Definition: recovery_behaviors.cpp:87
boost::shared_ptr
teb_local_planner::TebLocalPlannerROS::odom_helper_
base_local_planner::OdometryHelperRos odom_helper_
Provides an interface to receive the current velocity from the robot.
Definition: teb_local_planner_ros.h:450
teb_local_planner::PoseSE2::y
double & y()
Access the y-coordinate the pose.
Definition: pose_se2.h:206
teb_local_planner::TebLocalPlannerROS::costmap_converter_loader_
pluginlib::ClassLoader< costmap_converter::BaseCostmapToPolygons > costmap_converter_loader_
Load costmap converter plugins at runtime.
Definition: teb_local_planner_ros.h:452
teb_local_planner::TebOptimalPlanner
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
Definition: optimal_planner.h:136
teb_local_planner::TebLocalPlannerROS::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Pointer to the costmap ros wrapper, received from the navigation stack.
Definition: teb_local_planner_ros.h:435
teb_local_planner::TebLocalPlannerROS::validateFootprints
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...
Definition: teb_local_planner_ros.cpp:972
teb_local_planner::TebConfig::GoalTolerance::complete_global_plan
bool complete_global_plan
Definition: teb_config.h:123
tf2::getYaw
double getYaw(const A &a)
tf2_eigen.h
teb_local_planner::TebLocalPlannerROS::robot_goal_
PoseSE2 robot_goal_
Store current robot goal.
Definition: teb_local_planner_ros.h:465
teb_local_planner::TebConfig::configMutex
boost::mutex & configMutex()
Return the internal config mutex.
Definition: teb_config.h:425
base_local_planner::OdometryHelperRos::getOdom
void getOdom(nav_msgs::Odometry &base_odom)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
teb_local_planner::TebLocalPlannerROS::robot_vel_
geometry_msgs::Twist robot_vel_
Store current robot translational and angular velocity (vx, vy, omega)
Definition: teb_local_planner_ros.h:466
teb_local_planner_ros.h
teb_local_planner::TebLocalPlannerROS::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the teb plugin.
Definition: teb_local_planner_ros.cpp:129
teb_local_planner::TebLocalPlannerROS::robot_inscribed_radius_
double robot_inscribed_radius_
The radius of the inscribed circle of the robot (collision possible)
Definition: teb_local_planner_ros.h:475
teb_local_planner::TebConfig::loadRosParamFromNodeHandle
void loadRosParamFromNodeHandle(const ros::NodeHandle &nh)
Load parmeters from the ros param server.
Definition: teb_config.cpp:80
teb_local_planner::TebConfig::Trajectory::feasibility_check_lookahead_distance
double feasibility_check_lookahead_distance
Specify up to which distance (and with an index below feasibility_check_no_poses) from the robot the ...
Definition: teb_config.h:89
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
teb_local_planner::TebLocalPlannerROS::~TebLocalPlannerROS
~TebLocalPlannerROS()
Destructor of the plugin.
Definition: teb_local_planner_ros.cpp:113
teb_local_planner::TebLocalPlannerROS::time_last_infeasible_plan_
ros::Time time_last_infeasible_plan_
Store at which time stamp the last infeasible plan was detected.
Definition: teb_local_planner_ros.h:468
teb_local_planner::Point2dContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
Definition: distance_calculations.h:86
teb_local_planner::TebLocalPlannerROS::custom_obst_mutex_
boost::mutex custom_obst_mutex_
Mutex that locks the obstacle array (multi-threaded)
Definition: teb_local_planner_ros.h:457
XmlRpc::XmlRpcValue::TypeInt
TypeInt
teb_local_planner::TebConfig::GoalTolerance::theta_stopped_vel
double theta_stopped_vel
Below what maximum rotation velocity we consider the robot to be stopped in rotation.
Definition: teb_config.h:122
teb_local_planner::TebLocalPlannerROS::via_points_sub_
ros::Subscriber via_points_sub_
Subscriber for custom via-points received via a Path msg.
Definition: teb_local_planner_ros.h:460
teb_local_planner::TebConfig::Recovery::oscillation_recovery
bool oscillation_recovery
Try to detect and resolve oscillations between multiple solutions in the same equivalence class (robo...
Definition: teb_config.h:222
teb_local_planner::TebLocalPlannerROS::costmap_
costmap_2d::Costmap2D * costmap_
Pointer to the 2d costmap (obtained from the costmap ros wrapper)
Definition: teb_local_planner_ros.h:436
costmap_2d::Costmap2DROS::getBaseFrameID
const std::string & getBaseFrameID() const noexcept
teb_local_planner::PolygonObstacle::finalizePolygon
void finalizePolygon()
Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods.
Definition: obstacles.h:1112
cmd_vel_to_ackermann_drive.wheelbase
wheelbase
Definition: cmd_vel_to_ackermann_drive.py:52
teb_local_planner::TebConfig::hcp
struct teb_local_planner::TebConfig::HomotopyClasses hcp
costmap_2d::Costmap2D
ROS_WARN_ONCE
#define ROS_WARN_ONCE(...)
costmap_2d::calculateMinAndMaxDistances
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)
teb_local_planner::TebConfig::Obstacles::costmap_converter_plugin
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:139
costmap_2d::Costmap2D::mapToWorld
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
teb_local_planner::RotType::left
@ left
teb_local_planner::TebLocalPlannerROS::planner_
PlannerInterfacePtr planner_
Instance of the underlying optimal planner class.
Definition: teb_local_planner_ros.h:440
teb_local_planner::TebConfig::Obstacles::include_costmap_obstacles
bool include_costmap_obstacles
Specify whether the obstacles in the costmap should be taken into account directly.
Definition: teb_config.h:133
teb_local_planner::TebLocalPlannerROS::global_frame_
std::string global_frame_
The frame in which the controller will run.
Definition: teb_local_planner_ros.h:478
teb_local_planner::PolygonObstacle::pushBackVertex
void pushBackVertex(const Eigen::Ref< const Eigen::Vector2d > &vertex)
Add a vertex to the polygon (edge-point)
Definition: obstacles.h:1090
base_local_planner::OdometryHelperRos::getRobotVel
void getRobotVel(geometry_msgs::PoseStamped &robot_vel)
teb_local_planner::RotType
RotType
Symbols for left/none/right rotations
Definition: misc.h:89
teb_local_planner::TebLocalPlannerROS::TebLocalPlannerROS
TebLocalPlannerROS()
Default constructor of the teb plugin.
Definition: teb_local_planner_ros.cpp:105
teb_local_planner::TebConfig::Trajectory::global_plan_viapoint_sep
double global_plan_viapoint_sep
Min. separation between each two consecutive via-points extracted from the global plan (if negative: ...
Definition: teb_config.h:81
config
TebConfig config
Definition: test_optim_node.cpp:56
ROS_WARN_COND
#define ROS_WARN_COND(cond,...)
teb_local_planner::TebConfig::Trajectory::control_look_ahead_poses
int control_look_ahead_poses
Min angular resolution used during the costmap collision check. If not respected, intermediate sample...
Definition: teb_config.h:92
export_to_svg.line_end
list line_end
Definition: export_to_svg.py:229
teb_local_planner::FailureDetector::setBufferLength
void setBufferLength(int length)
Set buffer length (measurement history)
Definition: recovery_behaviors.h:112
teb_local_planner::TebLocalPlannerROS::estimateLocalGoalOrientation
double estimateLocalGoalOrientation(const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &local_goal, int current_goal_idx, const geometry_msgs::TransformStamped &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...
Definition: teb_local_planner_ros.cpp:863
pluginlib::PluginlibException
teb_local_planner::TebConfig::GoalTolerance::xy_goal_tolerance
double xy_goal_tolerance
Allowed final euclidean distance to the goal position.
Definition: teb_config.h:119
class_list_macros.h
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
teb_local_planner::TebLocalPlannerROS::tfPoseToEigenVector2dTransRot
static Eigen::Vector2d tfPoseToEigenVector2dTransRot(const tf::Pose &tf_vel)
Transform a tf::Pose type into a Eigen::Vector2d containing the translational and angular velocities.
Definition: teb_local_planner_ros.cpp:684
costmap_2d::Costmap2DROS::getRobotFootprint
const std::vector< geometry_msgs::Point > & getRobotFootprint() const noexcept
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
teb_local_planner::TebLocalPlannerROS::name_
std::string name_
For use with the ros nodehandle.
Definition: teb_local_planner_ros.h:480
teb_local_planner::TebConfig::Recovery::oscillation_filter_duration
double oscillation_filter_duration
Filter length/duration [sec] for the detection of oscillations.
Definition: teb_config.h:226
ROS_INFO_COND
#define ROS_INFO_COND(cond,...)
export_to_svg.point
list point
Definition: export_to_svg.py:223
XmlRpc::XmlRpcValue::TypeDouble
TypeDouble
teb_local_planner::TebConfig::recovery
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
teb_local_planner::TebConfig::Robot::max_vel_x_backwards
double max_vel_x_backwards
Maximum translational velocity of the robot for driving backwards.
Definition: teb_config.h:100
teb_local_planner::ObstaclePtr
boost::shared_ptr< Obstacle > ObstaclePtr
Abbrev. for shared obstacle pointers.
Definition: obstacles.h:329
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
teb_local_planner::TebLocalPlannerROS::visualization_
TebVisualizationPtr visualization_
Instance of the visualization class (local/global plan, obstacles, ...)
Definition: teb_local_planner_ros.h:443
teb_local_planner::CircularObstacle
Implements a 2D circular obstacle (point obstacle plus radius)
Definition: obstacles.h:483
ROS_DEBUG
#define ROS_DEBUG(...)
teb_local_planner::TebLocalPlannerROS::makeFootprintFromXMLRPC
static Point2dContainer makeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, const std::string &full_param_name)
Set the footprint from the given XmlRpcValue.
Definition: teb_local_planner_ros.cpp:1204
teb_local_planner::TebLocalPlannerROS::robot_base_frame_
std::string robot_base_frame_
Used as the base frame id of the robot.
Definition: teb_local_planner_ros.h:479
teb_local_planner::TebConfig::trajectory
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
teb_local_planner::TebLocalPlannerROS::cfg_
TebConfig cfg_
Config class that stores and manages all related parameters.
Definition: teb_local_planner_ros.h:445
tf2::ExtrapolationException
teb_local_planner::TebConfig::Obstacles::min_obstacle_dist
double min_obstacle_dist
Minimum desired separation from obstacles.
Definition: teb_config.h:129
teb_local_planner::FailureDetector::isOscillating
bool isOscillating() const
Check if the robot got stucked.
Definition: recovery_behaviors.cpp:116
teb_local_planner::TebLocalPlannerROS::customObstacleCB
void customObstacleCB(const costmap_converter::ObstacleArrayMsg::ConstPtr &obst_msg)
Callback for custom obstacles that are not obtained from the costmap.
Definition: teb_local_planner_ros.cpp:1056
teb_local_planner::TebConfig::Trajectory::global_plan_overwrite_orientation
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
Definition: teb_config.h:79
teb_local_planner::PoseSE2::theta
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: pose_se2.h:218
teb_local_planner::TebLocalPlannerROS::dynamic_recfg_
boost::shared_ptr< dynamic_reconfigure::Server< TebLocalPlannerReconfigureConfig > > dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
Definition: teb_local_planner_ros.h:455
ROS_INFO_ONCE
#define ROS_INFO_ONCE(...)
teb_local_planner::TebLocalPlannerROS::getRobotFootprintFromParamServer
static RobotFootprintModelPtr getRobotFootprintFromParamServer(const ros::NodeHandle &nh, const TebConfig &config)
Get the current robot footprint/contour model.
Definition: teb_local_planner_ros.cpp:1082
teb_local_planner::TebLocalPlannerROS::convertTransRotVelToSteeringAngle
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.
Definition: teb_local_planner_ros.cpp:958
teb_local_planner::PoseSE2::position
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:181
teb_local_planner::TebConfig::robot
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
teb_local_planner::TebLocalPlannerROS::time_last_oscillation_
ros::Time time_last_oscillation_
Store at which time stamp the last oscillation was detected.
Definition: teb_local_planner_ros.h:470
teb_local_planner::RotType::none
@ none
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
teb_local_planner::TebConfig::Trajectory::max_global_plan_lookahead_dist
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:83
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
teb_local_planner::TebConfig::GoalTolerance::trans_stopped_vel
double trans_stopped_vel
Below what maximum velocity we consider the robot to be stopped in translation.
Definition: teb_config.h:121
ROS_WARN
#define ROS_WARN(...)
costmap_2d::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
tf2_ros::Buffer
teb_local_planner::TebLocalPlannerROS::no_infeasible_plans_
int no_infeasible_plans_
Store how many times in a row the planner failed to find a feasible plan.
Definition: teb_local_planner_ros.h:469
teb_local_planner::TebVisualizationPtr
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
Definition: visualization.h:311
teb_local_planner::TebConfig::Recovery::oscillation_recovery_min_duration
double oscillation_recovery_min_duration
Minumum duration [sec] for which the recovery mode is activated after an oscillation is detected.
Definition: teb_config.h:225
teb_local_planner::TebConfig::Obstacles::costmap_obstacles_behind_robot_dist
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:134
tf2::LookupException
teb_local_planner::TebConfig::Trajectory::global_plan_prune_distance
double global_plan_prune_distance
Distance between robot and via_points of global plan which is used for pruning.
Definition: teb_config.h:84
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
tf::Transform
teb_local_planner::average_angles
double average_angles(const std::vector< double > &angles)
Return the average angle of an arbitrary number of given angles [rad].
Definition: misc.h:108
teb_local_planner::TebConfig::reconfigure
void reconfigure(TebLocalPlannerReconfigureConfig &cfg)
Reconfigure parameters from the dynamic_reconfigure config. Change parameters dynamically (e....
Definition: teb_config.cpp:221
tf2::ConnectivityException
XmlRpc::XmlRpcValue::getType
const Type & getType() const
ROS_FATAL
#define ROS_FATAL(...)
tf2::transformToEigen
Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform &t)
export_to_svg.line_start
list line_start
Definition: export_to_svg.py:228
teb_local_planner::TebConfig::GoalTolerance::yaw_goal_tolerance
double yaw_goal_tolerance
Allowed final orientation error.
Definition: teb_config.h:118
teb_local_planner::TebConfig::Obstacles::costmap_converter_spin_thread
bool costmap_converter_spin_thread
If true, the costmap converter invokes its callback queue in a different thread.
Definition: teb_config.h:140
teb_local_planner::TebConfig::goal_tolerance
struct teb_local_planner::TebConfig::GoalTolerance goal_tolerance
Goal tolerance related parameters.
teb_local_planner::TebLocalPlannerROS::transformGlobalPlan
bool transformGlobalPlan(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &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, geometry_msgs::TransformStamped *tf_plan_to_global=NULL) const
Transforms the global plan of the robot from the planner frame to the local frame (modified).
Definition: teb_local_planner_ros.cpp:737
XmlRpc::XmlRpcValue::TypeArray
TypeArray
teb_local_planner::TebLocalPlannerROS::via_point_mutex_
boost::mutex via_point_mutex_
Mutex that locks the via_points container (multi-threaded)
Definition: teb_local_planner_ros.h:462
teb_local_planner::TebConfig::Robot::use_proportional_saturation
bool use_proportional_saturation
Definition: teb_config.h:111
teb_local_planner::TebLocalPlannerROS::customViaPointsCB
void customViaPointsCB(const nav_msgs::Path::ConstPtr &via_points_msg)
Callback for custom via-points.
Definition: teb_local_planner_ros.cpp:1062
teb_local_planner::PointObstacle
Implements a 2D point obstacle.
Definition: obstacles.h:341
teb_local_planner::TebLocalPlannerROS::configureBackupModes
void configureBackupModes(std::vector< geometry_msgs::PoseStamped > &transformed_plan, int &goal_idx)
Definition: teb_local_planner_ros.cpp:982
teb_local_planner::TebLocalPlannerROS::failure_detector_
FailureDetector failure_detector_
Detect if the robot got stucked.
Definition: teb_local_planner_ros.h:446
teb_local_planner::TebLocalPlannerROS::goal_reached_
bool goal_reached_
store whether the goal is reached or not
Definition: teb_local_planner_ros.h:467
teb_local_planner::HomotopyClassPlanner
Local planner that explores alternative homotopy classes, create a plan for each alternative and fina...
Definition: homotopy_class_planner.h:144
teb_local_planner::TebConfig::Robot::max_vel_x
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:99
teb_local_planner::TebConfig::obstacles
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
teb_local_planner::PoseSE2
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:93
teb_local_planner::TebLocalPlannerROS::tf_
tf2_ros::Buffer * tf_
pointer to tf buffer
Definition: teb_local_planner_ros.h:437
teb_local_planner::TebLocalPlannerROS::updateObstacleContainerWithCustomObstacles
void updateObstacleContainerWithCustomObstacles()
Update internal obstacle vector based on custom messages received via subscriber.
Definition: teb_local_planner_ros.cpp:588
teb_local_planner::TebLocalPlannerROS::saturateVelocity
void saturateVelocity(double &vx, double &vy, double &omega, double max_vel_x, double max_vel_y, double max_vel_trans, double max_vel_theta, double max_vel_x_backwards) const
Saturate the translational and angular velocity to given limits.
Definition: teb_local_planner_ros.cpp:910
pluginlib::ClassLoader::createInstance
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
ros::Time
teb_local_planner::PoseSE2::orientationUnitVec
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:251
teb_local_planner::TebConfig::map_frame
std::string map_frame
Global planning frame.
Definition: teb_config.h:67
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
teb_local_planner::TebConfig::GoalTolerance::free_goal_vel
bool free_goal_vel
Allow the robot's velocity to be nonzero (usally max_vel) for planning purposes.
Definition: teb_config.h:120
costmap_2d::Costmap2DROS::getRobotPose
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
teb_local_planner::distance_points2d
double distance_points2d(const P1 &point1, const P2 &point2)
Calculate Euclidean distance between two 2D point datatypes.
Definition: misc.h:143
pluginlib::ClassLoader::getName
virtual std::string getName(const std::string &lookup_name)
teb_local_planner::TebLocalPlannerROS::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
Store the current global plan.
Definition: teb_local_planner_ros.h:448
teb_local_planner::TebConfig::HomotopyClasses::enable_homotopy_class_planning
bool enable_homotopy_class_planning
Activate homotopy class planning (Requires much more resources that simple planning,...
Definition: teb_config.h:185
teb_local_planner::TebVisualization
Forward Declaration.
Definition: visualization.h:116
teb_local_planner::TebConfig::Recovery::oscillation_v_eps
double oscillation_v_eps
Threshold for the average normalized linear velocity: if oscillation_v_eps and oscillation_omega_eps ...
Definition: teb_config.h:223
teb_local_planner::TebConfig::Obstacles::costmap_converter_rate
int costmap_converter_rate
The rate that defines how often the costmap_converter plugin processes the current costmap (the value...
Definition: teb_config.h:141
teb_local_planner::TebLocalPlannerROS::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the teb local planner is following.
Definition: teb_local_planner_ros.cpp:239
teb_local_planner::LineObstacle
Implements a 2D line obstacle.
Definition: obstacles.h:633
teb_local_planner::TebLocalPlannerROS::isGoalReached
bool isGoalReached()
Check if the goal pose has been achieved.
Definition: teb_local_planner_ros.cpp:501
ROS_ERROR
#define ROS_ERROR(...)
tf2::Quaternion
teb_local_planner::TebConfig::robot_model
RobotFootprintModelPtr robot_model
model of the robot's footprint
Definition: teb_config.h:69
tf2_geometry_msgs.h
costmap_2d::Costmap2D::getResolution
double getResolution() const
teb_local_planner::TebConfig::Recovery::shrink_horizon_backup
bool shrink_horizon_backup
Allows the planner to shrink the horizon temporary (50%) in case of automatically detected issues.
Definition: teb_config.h:220
teb_local_planner::TebLocalPlannerROS::costmap_converter_
boost::shared_ptr< costmap_converter::BaseCostmapToPolygons > costmap_converter_
Store the current costmap_converter
Definition: teb_local_planner_ros.h:453
teb_local_planner::TebConfig::Recovery::shrink_horizon_min_duration
double shrink_horizon_min_duration
Specify minimum duration for the reduced horizon in case an infeasible trajectory is detected.
Definition: teb_config.h:221
teb_local_planner::TebLocalPlannerROS::robot_circumscribed_radius
double robot_circumscribed_radius
The radius of the circumscribed circle of the robot.
Definition: teb_local_planner_ros.h:476
teb_local_planner::TebLocalPlannerROS::costmap_model_
boost::shared_ptr< base_local_planner::CostmapModel > costmap_model_
Definition: teb_local_planner_ros.h:444
teb_local_planner::TebConfig::Trajectory::feasibility_check_no_poses
int feasibility_check_no_poses
Specify up to which pose (under the feasibility_check_lookahead_distance) on the predicted plan the f...
Definition: teb_config.h:88
teb_local_planner::TebLocalPlannerROS::pruneGlobalPlan
bool pruneGlobalPlan(const tf2_ros::Buffer &tf, const geometry_msgs::PoseStamped &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.
Definition: teb_local_planner_ros.cpp:693
teb_local_planner::TebConfig::odom_topic
std::string odom_topic
Topic name of the odometry message, provided by the robot driver or simulator.
Definition: teb_config.h:66
ros::Rate
tf
teb_local_planner::TebLocalPlannerROS
Implements both nav_core::BaseLocalPlanner and mbf_costmap_core::CostmapController abstract interface...
Definition: teb_local_planner_ros.h:129
teb_local_planner::PlannerInterfacePtr
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it's subclasses.
Definition: planner_interface.h:239
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
teb_local_planner::TebLocalPlannerROS::custom_obst_sub_
ros::Subscriber custom_obst_sub_
Subscriber for custom obstacles received via a ObstacleMsg.
Definition: teb_local_planner_ros.h:456
costmap_2d::Costmap2DROS::getCostmap
Costmap2D * getCostmap() const
teb_local_planner::TebLocalPlannerROS::getNumberFromXMLRPC
static double getNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name)
Get a number from the given XmlRpcValue.
Definition: teb_local_planner_ros.cpp:1241
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
teb_local_planner::PolygonObstacle
Implements a polygon obstacle with an arbitrary number of vertices.
Definition: obstacles.h:934
costmap_2d::Costmap2DROS::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
tf_
tf2_ros::Buffer * tf_
tf2::TransformException
ROS_INFO
#define ROS_INFO(...)
teb_local_planner::TebConfig::Robot::min_turning_radius
double min_turning_radius
Minimum turning radius of a carlike robot (diff-drive robot: zero);.
Definition: teb_config.h:107
teb_local_planner
Definition: distance_calculations.h:46
costmap_2d::Costmap2D::getCost
unsigned char getCost(unsigned int mx, unsigned int my) const
teb_local_planner::TebConfig::Robot::wheelbase
double wheelbase
The distance between the drive shaft and steering axle (only required for a carlike robot with 'cmd_a...
Definition: teb_config.h:108
teb_local_planner::TebLocalPlannerROS::last_preferred_rotdir_
RotType last_preferred_rotdir_
Store recent preferred turning direction.
Definition: teb_local_planner_ros.h:471
teb_local_planner::TebConfig::Robot::cmd_angle_instead_rotvel
bool cmd_angle_instead_rotvel
Substitute the rotational velocity in the commanded velocity message by the corresponding steering an...
Definition: teb_config.h:109
ros::Duration
teb_local_planner::TebLocalPlannerROS::footprint_spec_
std::vector< geometry_msgs::Point > footprint_spec_
Store the footprint of the robot.
Definition: teb_local_planner_ros.h:474
teb_local_planner::TebLocalPlannerROS::initialized_
bool initialized_
Keeps track about the correct initialization of this class.
Definition: teb_local_planner_ros.h:483
costmap_2d::Costmap2DROS
teb_local_planner::TebConfig::Robot::is_footprint_dynamic
bool is_footprint_dynamic
Definition: teb_config.h:110
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
XmlRpc::XmlRpcValue
teb_local_planner::TebConfig::Robot::max_vel_theta
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:103
nav_core::BaseLocalPlanner
teb_local_planner::TebLocalPlannerROS::last_cmd_
geometry_msgs::Twist last_cmd_
Store the last control command generated in computeVelocityCommands()
Definition: teb_local_planner_ros.h:472
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
ros::NodeHandle
base_local_planner::stopped
bool stopped(const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity)
teb_local_planner::TebConfig::Recovery::oscillation_omega_eps
double oscillation_omega_eps
Threshold for the average normalized angular velocity: if oscillation_v_eps and oscillation_omega_eps...
Definition: teb_config.h:224
teb_local_planner::RotType::right
@ right
teb_local_planner::TebLocalPlannerROS::reconfigureCB
void reconfigureCB(TebLocalPlannerReconfigureConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
Definition: teb_local_planner_ros.cpp:117
ros::Time::now
static Time now()
teb_local_planner::TebLocalPlannerROS::obstacles_
ObstContainer obstacles_
Obstacle vector that should be considered during local trajectory optimization.
Definition: teb_local_planner_ros.h:441


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15