optimal_planner.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 // g2o custom edges and vertices for the TEB planner
52 
53 #include <memory>
54 #include <limits>
55 
56 
57 namespace teb_local_planner
58 {
59 
60 // ============== Implementation ===================
61 
62 TebOptimalPlanner::TebOptimalPlanner() : cfg_(NULL), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), prefer_rotdir_(RotType::none),
63  initialized_(false), optimized_(false)
64 {
65 }
66 
68 {
69  initialize(cfg, obstacles, visual, via_points);
70 }
71 
73 {
74  clearGraph();
75  // free dynamically allocated memory
76  //if (optimizer_)
77  // g2o::Factory::destroy();
78  //g2o::OptimizationAlgorithmFactory::destroy();
79  //g2o::HyperGraphActionLibrary::destroy();
80 }
81 
83 {
84  // init optimizer (set solver and block ordering settings)
86 
87  cfg_ = &cfg;
88  obstacles_ = obstacles;
90  cost_ = HUGE_VAL;
93 
94  vel_start_.first = true;
95  vel_start_.second.linear.x = 0;
96  vel_start_.second.linear.y = 0;
97  vel_start_.second.angular.z = 0;
98 
99  vel_goal_.first = true;
100  vel_goal_.second.linear.x = 0;
101  vel_goal_.second.linear.y = 0;
102  vel_goal_.second.angular.z = 0;
103  initialized_ = true;
104 }
105 
106 
108 {
109  visualization_ = visualization;
110 }
111 
113 {
114  if (!visualization_)
115  return;
116 
117  visualization_->publishLocalPlanAndPoses(teb_);
118 
119  if (teb_.sizePoses() > 0)
120  visualization_->publishRobotFootprintModel(teb_.Pose(0), *cfg_->robot_model);
121 
123  visualization_->publishFeedbackMessage(*this, *obstacles_);
124 
125 }
126 
127 
128 /*
129  * registers custom vertices and edges in g2o framework
130  */
132 {
133  g2o::Factory* factory = g2o::Factory::instance();
134  factory->registerType("VERTEX_POSE", new g2o::HyperGraphElementCreator<VertexPose>);
135  factory->registerType("VERTEX_TIMEDIFF", new g2o::HyperGraphElementCreator<VertexTimeDiff>);
136 
137  factory->registerType("EDGE_TIME_OPTIMAL", new g2o::HyperGraphElementCreator<EdgeTimeOptimal>);
138  factory->registerType("EDGE_SHORTEST_PATH", new g2o::HyperGraphElementCreator<EdgeShortestPath>);
139  factory->registerType("EDGE_VELOCITY", new g2o::HyperGraphElementCreator<EdgeVelocity>);
140  factory->registerType("EDGE_VELOCITY_HOLONOMIC", new g2o::HyperGraphElementCreator<EdgeVelocityHolonomic>);
141  factory->registerType("EDGE_ACCELERATION", new g2o::HyperGraphElementCreator<EdgeAcceleration>);
142  factory->registerType("EDGE_ACCELERATION_START", new g2o::HyperGraphElementCreator<EdgeAccelerationStart>);
143  factory->registerType("EDGE_ACCELERATION_GOAL", new g2o::HyperGraphElementCreator<EdgeAccelerationGoal>);
144  factory->registerType("EDGE_ACCELERATION_HOLONOMIC", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomic>);
145  factory->registerType("EDGE_ACCELERATION_HOLONOMIC_START", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicStart>);
146  factory->registerType("EDGE_ACCELERATION_HOLONOMIC_GOAL", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicGoal>);
147  factory->registerType("EDGE_KINEMATICS_DIFF_DRIVE", new g2o::HyperGraphElementCreator<EdgeKinematicsDiffDrive>);
148  factory->registerType("EDGE_KINEMATICS_CARLIKE", new g2o::HyperGraphElementCreator<EdgeKinematicsCarlike>);
149  factory->registerType("EDGE_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeObstacle>);
150  factory->registerType("EDGE_INFLATED_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeInflatedObstacle>);
151  factory->registerType("EDGE_DYNAMIC_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeDynamicObstacle>);
152  factory->registerType("EDGE_VIA_POINT", new g2o::HyperGraphElementCreator<EdgeViaPoint>);
153  factory->registerType("EDGE_PREFER_ROTDIR", new g2o::HyperGraphElementCreator<EdgePreferRotDir>);
154  return;
155 }
156 
157 /*
158  * initialize g2o optimizer. Set solver settings here.
159  * Return: pointer to new SparseOptimizer Object.
160  */
162 {
163  // Call register_g2o_types once, even for multiple TebOptimalPlanner instances (thread-safe)
164  static boost::once_flag flag = BOOST_ONCE_INIT;
165  boost::call_once(&registerG2OTypes, flag);
166 
167  // allocating the optimizer
168  boost::shared_ptr<g2o::SparseOptimizer> optimizer = boost::make_shared<g2o::SparseOptimizer>();
169  std::unique_ptr<TEBLinearSolver> linear_solver(new TEBLinearSolver()); // see typedef in optimization.h
170  linear_solver->setBlockOrdering(true);
171  std::unique_ptr<TEBBlockSolver> block_solver(new TEBBlockSolver(std::move(linear_solver)));
172  g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(std::move(block_solver));
173 
174  optimizer->setAlgorithm(solver);
175 
176  optimizer->initMultiThreading(); // required for >Eigen 3.1
177 
178  return optimizer;
179 }
180 
181 
182 bool TebOptimalPlanner::optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards,
183  double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
184 {
185  if (cfg_->optim.optimization_activate==false)
186  return false;
187 
188  bool success = false;
189  optimized_ = false;
190 
191  double weight_multiplier = 1.0;
192 
193  // TODO(roesmann): we introduced the non-fast mode with the support of dynamic obstacles
194  // (which leads to better results in terms of x-y-t homotopy planning).
195  // however, we have not tested this mode intensively yet, so we keep
196  // the legacy fast mode as default until we finish our tests.
198 
199  for(int i=0; i<iterations_outerloop; ++i)
200  {
202  {
203  //teb_.autoResize(cfg_->trajectory.dt_ref, cfg_->trajectory.dt_hysteresis, cfg_->trajectory.min_samples, cfg_->trajectory.max_samples);
205 
206  }
207 
208  success = buildGraph(weight_multiplier);
209  if (!success)
210  {
211  clearGraph();
212  return false;
213  }
214  success = optimizeGraph(iterations_innerloop, false);
215  if (!success)
216  {
217  clearGraph();
218  return false;
219  }
220  optimized_ = true;
221 
222  if (compute_cost_afterwards && i==iterations_outerloop-1) // compute cost vec only in the last iteration
223  computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
224 
225  clearGraph();
226 
227  weight_multiplier *= cfg_->optim.weight_adapt_factor;
228  }
229 
230  return true;
231 }
232 
234 {
235  vel_start_.first = true;
236  vel_start_.second.linear.x = vel_start.linear.x;
237  vel_start_.second.linear.y = vel_start.linear.y;
238  vel_start_.second.angular.z = vel_start.angular.z;
239 }
240 
242 {
243  vel_goal_.first = true;
244  vel_goal_.second = vel_goal;
245 }
246 
247 bool TebOptimalPlanner::plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
248 {
249  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
250  if (!teb_.isInit())
251  {
254  }
255  else // warm start
256  {
257  PoseSE2 start_(initial_plan.front().pose);
258  PoseSE2 goal_(initial_plan.back().pose);
259  if (teb_.sizePoses()>0
260  && (goal_.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist
261  && fabs(g2o::normalize_theta(goal_.theta() - teb_.BackPose().theta())) < cfg_->trajectory.force_reinit_new_goal_angular) // actual warm start!
262  teb_.updateAndPruneTEB(start_, goal_, cfg_->trajectory.min_samples); // update TEB
263  else // goal too far away -> reinit
264  {
265  ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
269  }
270  }
271  if (start_vel)
272  setVelocityStart(*start_vel);
273  if (free_goal_vel)
275  else
276  vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified)
277 
278  // now optimize
280 }
281 
282 
283 bool TebOptimalPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
284 {
285  PoseSE2 start_(start);
286  PoseSE2 goal_(goal);
287  return plan(start_, goal_, start_vel);
288 }
289 
290 bool TebOptimalPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
291 {
292  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
293  if (!teb_.isInit())
294  {
295  // init trajectory
296  teb_.initTrajectoryToGoal(start, goal, 0, cfg_->robot.max_vel_x, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion); // 0 intermediate samples, but dt=1 -> autoResize will add more samples before calling first optimization
297  }
298  else // warm start
299  {
300  if (teb_.sizePoses() > 0
302  && fabs(g2o::normalize_theta(goal.theta() - teb_.BackPose().theta())) < cfg_->trajectory.force_reinit_new_goal_angular) // actual warm start!
304  else // goal too far away -> reinit
305  {
306  ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
309  }
310  }
311  if (start_vel)
312  setVelocityStart(*start_vel);
313  if (free_goal_vel)
315  else
316  vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified)
317 
318  // now optimize
320 }
321 
322 
323 bool TebOptimalPlanner::buildGraph(double weight_multiplier)
324 {
325  if (!optimizer_->edges().empty() || !optimizer_->vertices().empty())
326  {
327  ROS_WARN("Cannot build graph, because it is not empty. Call graphClear()!");
328  return false;
329  }
330 
331  optimizer_->setComputeBatchStatistics(cfg_->recovery.divergence_detection_enable);
332 
333  // add TEB vertices
334  AddTEBVertices();
335 
336  // add Edges (local cost functions)
338  AddEdgesObstaclesLegacy(weight_multiplier);
339  else
340  AddEdgesObstacles(weight_multiplier);
341 
344 
346 
348 
350 
352 
354 
356  AddEdgesKinematicsDiffDrive(); // we have a differential drive robot
357  else
358  AddEdgesKinematicsCarlike(); // we have a carlike robot since the turning radius is bounded from below.
359 
361 
364 
365  return true;
366 }
367 
368 bool TebOptimalPlanner::optimizeGraph(int no_iterations,bool clear_after)
369 {
370  if (cfg_->robot.max_vel_x<0.01)
371  {
372  ROS_WARN("optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted...");
373  if (clear_after) clearGraph();
374  return false;
375  }
376 
378  {
379  ROS_WARN("optimizeGraph(): TEB is empty or has too less elements. Skipping optimization.");
380  if (clear_after) clearGraph();
381  return false;
382  }
383 
385  optimizer_->initializeOptimization();
386 
387  int iter = optimizer_->optimize(no_iterations);
388 
389  // Save Hessian for visualization
390  // g2o::OptimizationAlgorithmLevenberg* lm = dynamic_cast<g2o::OptimizationAlgorithmLevenberg*> (optimizer_->solver());
391  // lm->solver()->saveHessian("~/MasterThesis/Matlab/Hessian.txt");
392 
393  if(!iter)
394  {
395  ROS_ERROR("optimizeGraph(): Optimization failed! iter=%i", iter);
396  return false;
397  }
398 
399  if (clear_after) clearGraph();
400 
401  return true;
402 }
403 
405 {
406  // clear optimizer states
407  if (optimizer_)
408  {
409  // we will delete all edges but keep the vertices.
410  // before doing so, we will delete the link from the vertices to the edges.
411  auto& vertices = optimizer_->vertices();
412  for(auto& v : vertices)
413  v.second->edges().clear();
414 
415  optimizer_->vertices().clear(); // necessary, because optimizer->clear deletes pointer-targets (therefore it deletes TEB states!)
416  optimizer_->clear();
417  }
418 }
419 
420 
421 
423 {
424  // add vertices to graph
425  ROS_DEBUG_COND(cfg_->optim.optimization_verbose, "Adding TEB vertices ...");
426  unsigned int id_counter = 0; // used for vertices ids
428  auto iter_obstacle = obstacles_per_vertex_.begin();
429  for (int i=0; i<teb_.sizePoses(); ++i)
430  {
431  teb_.PoseVertex(i)->setId(id_counter++);
432  optimizer_->addVertex(teb_.PoseVertex(i));
433  if (teb_.sizeTimeDiffs()!=0 && i<teb_.sizeTimeDiffs())
434  {
435  teb_.TimeDiffVertex(i)->setId(id_counter++);
436  optimizer_->addVertex(teb_.TimeDiffVertex(i));
437  }
438  iter_obstacle->clear();
439  (iter_obstacle++)->reserve(obstacles_->size());
440  }
441 }
442 
443 
444 void TebOptimalPlanner::AddEdgesObstacles(double weight_multiplier)
445 {
446  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr )
447  return; // if weight equals zero skip adding edges!
448 
449 
451 
452  Eigen::Matrix<double,1,1> information;
453  information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
454 
455  Eigen::Matrix<double,2,2> information_inflated;
456  information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
457  information_inflated(1,1) = cfg_->optim.weight_inflation;
458  information_inflated(0,1) = information_inflated(1,0) = 0;
459 
460  auto iter_obstacle = obstacles_per_vertex_.begin();
461 
462  auto create_edge = [inflated, &information, &information_inflated, this] (int index, const Obstacle* obstacle) {
463  if (inflated)
464  {
465  EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
466  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
467  dist_bandpt_obst->setInformation(information_inflated);
468  dist_bandpt_obst->setParameters(*cfg_, obstacle);
469  optimizer_->addEdge(dist_bandpt_obst);
470  }
471  else
472  {
473  EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
474  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
475  dist_bandpt_obst->setInformation(information);
476  dist_bandpt_obst->setParameters(*cfg_, obstacle);
477  optimizer_->addEdge(dist_bandpt_obst);
478  };
479  };
480 
481  // iterate all teb points, skipping the last and, if the EdgeVelocityObstacleRatio edges should not be created, the first one too
482  const int first_vertex = cfg_->optim.weight_velocity_obstacle_ratio == 0 ? 1 : 0;
483  for (int i = first_vertex; i < teb_.sizePoses() - 1; ++i)
484  {
485  double left_min_dist = std::numeric_limits<double>::max();
486  double right_min_dist = std::numeric_limits<double>::max();
487  ObstaclePtr left_obstacle;
488  ObstaclePtr right_obstacle;
489 
490  const Eigen::Vector2d pose_orient = teb_.Pose(i).orientationUnitVec();
491 
492  // iterate obstacles
493  for (const ObstaclePtr& obst : *obstacles_)
494  {
495  // we handle dynamic obstacles differently below
496  if(cfg_->obstacles.include_dynamic_obstacles && obst->isDynamic())
497  continue;
498 
499  // calculate distance to robot model
500  double dist = cfg_->robot_model->calculateDistance(teb_.Pose(i), obst.get());
501 
502  // force considering obstacle if really close to the current pose
503  if (dist < cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_force_inclusion_factor)
504  {
505  iter_obstacle->push_back(obst);
506  continue;
507  }
508  // cut-off distance
510  continue;
511 
512  // determine side (left or right) and assign obstacle if closer than the previous one
513  if (cross2d(pose_orient, obst->getCentroid() - teb_.Pose(i).position()) > 0) // left
514  {
515  if (dist < left_min_dist)
516  {
517  left_min_dist = dist;
518  left_obstacle = obst;
519  }
520  }
521  else
522  {
523  if (dist < right_min_dist)
524  {
525  right_min_dist = dist;
526  right_obstacle = obst;
527  }
528  }
529  }
530 
531  if (left_obstacle)
532  iter_obstacle->push_back(left_obstacle);
533  if (right_obstacle)
534  iter_obstacle->push_back(right_obstacle);
535 
536  // continue here to ignore obstacles for the first pose, but use them later to create the EdgeVelocityObstacleRatio edges
537  if (i == 0)
538  {
539  ++iter_obstacle;
540  continue;
541  }
542 
543  // create obstacle edges
544  for (const ObstaclePtr obst : *iter_obstacle)
545  create_edge(i, obst.get());
546  ++iter_obstacle;
547  }
548 }
549 
550 
551 void TebOptimalPlanner::AddEdgesObstaclesLegacy(double weight_multiplier)
552 {
553  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr)
554  return; // if weight equals zero skip adding edges!
555 
556  Eigen::Matrix<double,1,1> information;
557  information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
558 
559  Eigen::Matrix<double,2,2> information_inflated;
560  information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
561  information_inflated(1,1) = cfg_->optim.weight_inflation;
562  information_inflated(0,1) = information_inflated(1,0) = 0;
563 
565 
566  for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
567  {
568  if (cfg_->obstacles.include_dynamic_obstacles && (*obst)->isDynamic()) // we handle dynamic obstacles differently below
569  continue;
570 
571  int index;
572 
574  index = teb_.sizePoses() / 2;
575  else
576  index = teb_.findClosestTrajectoryPose(*(obst->get()));
577 
578 
579  // check if obstacle is outside index-range between start and goal
580  if ( (index <= 1) || (index > teb_.sizePoses()-2) ) // start and goal are fixed and findNearestBandpoint finds first or last conf if intersection point is outside the range
581  continue;
582 
583  if (inflated)
584  {
585  EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
586  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
587  dist_bandpt_obst->setInformation(information_inflated);
588  dist_bandpt_obst->setParameters(*cfg_, obst->get());
589  optimizer_->addEdge(dist_bandpt_obst);
590  }
591  else
592  {
593  EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
594  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
595  dist_bandpt_obst->setInformation(information);
596  dist_bandpt_obst->setParameters(*cfg_, obst->get());
597  optimizer_->addEdge(dist_bandpt_obst);
598  }
599 
600  for (int neighbourIdx=0; neighbourIdx < floor(cfg_->obstacles.obstacle_poses_affected/2); neighbourIdx++)
601  {
602  if (index+neighbourIdx < teb_.sizePoses())
603  {
604  if (inflated)
605  {
606  EdgeInflatedObstacle* dist_bandpt_obst_n_r = new EdgeInflatedObstacle;
607  dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
608  dist_bandpt_obst_n_r->setInformation(information_inflated);
609  dist_bandpt_obst_n_r->setParameters(*cfg_, obst->get());
610  optimizer_->addEdge(dist_bandpt_obst_n_r);
611  }
612  else
613  {
614  EdgeObstacle* dist_bandpt_obst_n_r = new EdgeObstacle;
615  dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
616  dist_bandpt_obst_n_r->setInformation(information);
617  dist_bandpt_obst_n_r->setParameters(*cfg_, obst->get());
618  optimizer_->addEdge(dist_bandpt_obst_n_r);
619  }
620  }
621  if ( index - neighbourIdx >= 0) // needs to be casted to int to allow negative values
622  {
623  if (inflated)
624  {
625  EdgeInflatedObstacle* dist_bandpt_obst_n_l = new EdgeInflatedObstacle;
626  dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
627  dist_bandpt_obst_n_l->setInformation(information_inflated);
628  dist_bandpt_obst_n_l->setParameters(*cfg_, obst->get());
629  optimizer_->addEdge(dist_bandpt_obst_n_l);
630  }
631  else
632  {
633  EdgeObstacle* dist_bandpt_obst_n_l = new EdgeObstacle;
634  dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
635  dist_bandpt_obst_n_l->setInformation(information);
636  dist_bandpt_obst_n_l->setParameters(*cfg_, obst->get());
637  optimizer_->addEdge(dist_bandpt_obst_n_l);
638  }
639  }
640  }
641 
642  }
643 }
644 
645 
646 void TebOptimalPlanner::AddEdgesDynamicObstacles(double weight_multiplier)
647 {
648  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==NULL )
649  return; // if weight equals zero skip adding edges!
650 
651  Eigen::Matrix<double,2,2> information;
652  information(0,0) = cfg_->optim.weight_dynamic_obstacle * weight_multiplier;
653  information(1,1) = cfg_->optim.weight_dynamic_obstacle_inflation;
654  information(0,1) = information(1,0) = 0;
655 
656  for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
657  {
658  if (!(*obst)->isDynamic())
659  continue;
660 
661  // Skip first and last pose, as they are fixed
662  double time = teb_.TimeDiff(0);
663  for (int i=1; i < teb_.sizePoses() - 1; ++i)
664  {
665  EdgeDynamicObstacle* dynobst_edge = new EdgeDynamicObstacle(time);
666  dynobst_edge->setVertex(0,teb_.PoseVertex(i));
667  dynobst_edge->setInformation(information);
668  dynobst_edge->setParameters(*cfg_, obst->get());
669  optimizer_->addEdge(dynobst_edge);
670  time += teb_.TimeDiff(i); // we do not need to check the time diff bounds, since we iterate to "< sizePoses()-1".
671  }
672  }
673 }
674 
676 {
677  if (cfg_->optim.weight_viapoint==0 || via_points_==NULL || via_points_->empty() )
678  return; // if weight equals zero skip adding edges!
679 
680  int start_pose_idx = 0;
681 
682  int n = teb_.sizePoses();
683  if (n<3) // we do not have any degrees of freedom for reaching via-points
684  return;
685 
686  for (ViaPointContainer::const_iterator vp_it = via_points_->begin(); vp_it != via_points_->end(); ++vp_it)
687  {
688 
689  int index = teb_.findClosestTrajectoryPose(*vp_it, NULL, start_pose_idx);
691  start_pose_idx = index+2; // skip a point to have a DOF inbetween for further via-points
692 
693  // check if point conicides with goal or is located behind it
694  if ( index > n-2 )
695  index = n-2; // set to a pose before the goal, since we can move it away!
696  // check if point coincides with start or is located before it
697  if ( index < 1)
698  {
700  {
701  index = 1; // try to connect the via point with the second (and non-fixed) pose. It is likely that autoresize adds new poses inbetween later.
702  }
703  else
704  {
705  ROS_DEBUG("TebOptimalPlanner::AddEdgesViaPoints(): skipping a via-point that is close or behind the current robot pose.");
706  continue; // skip via points really close or behind the current robot pose
707  }
708  }
709  Eigen::Matrix<double,1,1> information;
710  information.fill(cfg_->optim.weight_viapoint);
711 
712  EdgeViaPoint* edge_viapoint = new EdgeViaPoint;
713  edge_viapoint->setVertex(0,teb_.PoseVertex(index));
714  edge_viapoint->setInformation(information);
715  edge_viapoint->setParameters(*cfg_, &(*vp_it));
716  optimizer_->addEdge(edge_viapoint);
717  }
718 }
719 
721 {
722  if (cfg_->robot.max_vel_y == 0) // non-holonomic robot
723  {
725  return; // if weight equals zero skip adding edges!
726 
727  int n = teb_.sizePoses();
728  Eigen::Matrix<double,2,2> information;
729  information(0,0) = cfg_->optim.weight_max_vel_x;
730  information(1,1) = cfg_->optim.weight_max_vel_theta;
731  information(0,1) = 0.0;
732  information(1,0) = 0.0;
733 
734  for (int i=0; i < n - 1; ++i)
735  {
736  EdgeVelocity* velocity_edge = new EdgeVelocity;
737  velocity_edge->setVertex(0,teb_.PoseVertex(i));
738  velocity_edge->setVertex(1,teb_.PoseVertex(i+1));
739  velocity_edge->setVertex(2,teb_.TimeDiffVertex(i));
740  velocity_edge->setInformation(information);
741  velocity_edge->setTebConfig(*cfg_);
742  optimizer_->addEdge(velocity_edge);
743  }
744  }
745  else // holonomic-robot
746  {
748  return; // if weight equals zero skip adding edges!
749 
750  int n = teb_.sizePoses();
751  Eigen::Matrix<double,3,3> information;
752  information.fill(0);
753  information(0,0) = cfg_->optim.weight_max_vel_x;
754  information(1,1) = cfg_->optim.weight_max_vel_y;
755  information(2,2) = cfg_->optim.weight_max_vel_theta;
756 
757  for (int i=0; i < n - 1; ++i)
758  {
759  EdgeVelocityHolonomic* velocity_edge = new EdgeVelocityHolonomic;
760  velocity_edge->setVertex(0,teb_.PoseVertex(i));
761  velocity_edge->setVertex(1,teb_.PoseVertex(i+1));
762  velocity_edge->setVertex(2,teb_.TimeDiffVertex(i));
763  velocity_edge->setInformation(information);
764  velocity_edge->setTebConfig(*cfg_);
765  optimizer_->addEdge(velocity_edge);
766  }
767 
768  }
769 }
770 
772 {
774  return; // if weight equals zero skip adding edges!
775 
776  int n = teb_.sizePoses();
777 
778  if (cfg_->robot.max_vel_y == 0 || cfg_->robot.acc_lim_y == 0) // non-holonomic robot
779  {
780  Eigen::Matrix<double,2,2> information;
781  information.fill(0);
782  information(0,0) = cfg_->optim.weight_acc_lim_x;
783  information(1,1) = cfg_->optim.weight_acc_lim_theta;
784 
785  // check if an initial velocity should be taken into accound
786  if (vel_start_.first)
787  {
788  EdgeAccelerationStart* acceleration_edge = new EdgeAccelerationStart;
789  acceleration_edge->setVertex(0,teb_.PoseVertex(0));
790  acceleration_edge->setVertex(1,teb_.PoseVertex(1));
791  acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0));
792  acceleration_edge->setInitialVelocity(vel_start_.second);
793  acceleration_edge->setInformation(information);
794  acceleration_edge->setTebConfig(*cfg_);
795  optimizer_->addEdge(acceleration_edge);
796  }
797 
798  // now add the usual acceleration edge for each tuple of three teb poses
799  for (int i=0; i < n - 2; ++i)
800  {
801  EdgeAcceleration* acceleration_edge = new EdgeAcceleration;
802  acceleration_edge->setVertex(0,teb_.PoseVertex(i));
803  acceleration_edge->setVertex(1,teb_.PoseVertex(i+1));
804  acceleration_edge->setVertex(2,teb_.PoseVertex(i+2));
805  acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i));
806  acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1));
807  acceleration_edge->setInformation(information);
808  acceleration_edge->setTebConfig(*cfg_);
809  optimizer_->addEdge(acceleration_edge);
810  }
811 
812  // check if a goal velocity should be taken into accound
813  if (vel_goal_.first)
814  {
815  EdgeAccelerationGoal* acceleration_edge = new EdgeAccelerationGoal;
816  acceleration_edge->setVertex(0,teb_.PoseVertex(n-2));
817  acceleration_edge->setVertex(1,teb_.PoseVertex(n-1));
818  acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 ));
819  acceleration_edge->setGoalVelocity(vel_goal_.second);
820  acceleration_edge->setInformation(information);
821  acceleration_edge->setTebConfig(*cfg_);
822  optimizer_->addEdge(acceleration_edge);
823  }
824  }
825  else // holonomic robot
826  {
827  Eigen::Matrix<double,3,3> information;
828  information.fill(0);
829  information(0,0) = cfg_->optim.weight_acc_lim_x;
830  information(1,1) = cfg_->optim.weight_acc_lim_y;
831  information(2,2) = cfg_->optim.weight_acc_lim_theta;
832 
833  // check if an initial velocity should be taken into accound
834  if (vel_start_.first)
835  {
836  EdgeAccelerationHolonomicStart* acceleration_edge = new EdgeAccelerationHolonomicStart;
837  acceleration_edge->setVertex(0,teb_.PoseVertex(0));
838  acceleration_edge->setVertex(1,teb_.PoseVertex(1));
839  acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0));
840  acceleration_edge->setInitialVelocity(vel_start_.second);
841  acceleration_edge->setInformation(information);
842  acceleration_edge->setTebConfig(*cfg_);
843  optimizer_->addEdge(acceleration_edge);
844  }
845 
846  // now add the usual acceleration edge for each tuple of three teb poses
847  for (int i=0; i < n - 2; ++i)
848  {
849  EdgeAccelerationHolonomic* acceleration_edge = new EdgeAccelerationHolonomic;
850  acceleration_edge->setVertex(0,teb_.PoseVertex(i));
851  acceleration_edge->setVertex(1,teb_.PoseVertex(i+1));
852  acceleration_edge->setVertex(2,teb_.PoseVertex(i+2));
853  acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i));
854  acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1));
855  acceleration_edge->setInformation(information);
856  acceleration_edge->setTebConfig(*cfg_);
857  optimizer_->addEdge(acceleration_edge);
858  }
859 
860  // check if a goal velocity should be taken into accound
861  if (vel_goal_.first)
862  {
863  EdgeAccelerationHolonomicGoal* acceleration_edge = new EdgeAccelerationHolonomicGoal;
864  acceleration_edge->setVertex(0,teb_.PoseVertex(n-2));
865  acceleration_edge->setVertex(1,teb_.PoseVertex(n-1));
866  acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 ));
867  acceleration_edge->setGoalVelocity(vel_goal_.second);
868  acceleration_edge->setInformation(information);
869  acceleration_edge->setTebConfig(*cfg_);
870  optimizer_->addEdge(acceleration_edge);
871  }
872  }
873 }
874 
875 
876 
878 {
879  if (cfg_->optim.weight_optimaltime==0)
880  return; // if weight equals zero skip adding edges!
881 
882  Eigen::Matrix<double,1,1> information;
883  information.fill(cfg_->optim.weight_optimaltime);
884 
885  for (int i=0; i < teb_.sizeTimeDiffs(); ++i)
886  {
887  EdgeTimeOptimal* timeoptimal_edge = new EdgeTimeOptimal;
888  timeoptimal_edge->setVertex(0,teb_.TimeDiffVertex(i));
889  timeoptimal_edge->setInformation(information);
890  timeoptimal_edge->setTebConfig(*cfg_);
891  optimizer_->addEdge(timeoptimal_edge);
892  }
893 }
894 
896 {
898  return; // if weight equals zero skip adding edges!
899 
900  Eigen::Matrix<double,1,1> information;
901  information.fill(cfg_->optim.weight_shortest_path);
902 
903  for (int i=0; i < teb_.sizePoses()-1; ++i)
904  {
905  EdgeShortestPath* shortest_path_edge = new EdgeShortestPath;
906  shortest_path_edge->setVertex(0,teb_.PoseVertex(i));
907  shortest_path_edge->setVertex(1,teb_.PoseVertex(i+1));
908  shortest_path_edge->setInformation(information);
909  shortest_path_edge->setTebConfig(*cfg_);
910  optimizer_->addEdge(shortest_path_edge);
911  }
912 }
913 
914 
915 
917 {
919  return; // if weight equals zero skip adding edges!
920 
921  // create edge for satisfiying kinematic constraints
922  Eigen::Matrix<double,2,2> information_kinematics;
923  information_kinematics.fill(0.0);
924  information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
925  information_kinematics(1, 1) = cfg_->optim.weight_kinematics_forward_drive;
926 
927  for (int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only
928  {
929  EdgeKinematicsDiffDrive* kinematics_edge = new EdgeKinematicsDiffDrive;
930  kinematics_edge->setVertex(0,teb_.PoseVertex(i));
931  kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));
932  kinematics_edge->setInformation(information_kinematics);
933  kinematics_edge->setTebConfig(*cfg_);
934  optimizer_->addEdge(kinematics_edge);
935  }
936 }
937 
939 {
941  return; // if weight equals zero skip adding edges!
942 
943  // create edge for satisfiying kinematic constraints
944  Eigen::Matrix<double,2,2> information_kinematics;
945  information_kinematics.fill(0.0);
946  information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
947  information_kinematics(1, 1) = cfg_->optim.weight_kinematics_turning_radius;
948 
949  for (int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only
950  {
951  EdgeKinematicsCarlike* kinematics_edge = new EdgeKinematicsCarlike;
952  kinematics_edge->setVertex(0,teb_.PoseVertex(i));
953  kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));
954  kinematics_edge->setInformation(information_kinematics);
955  kinematics_edge->setTebConfig(*cfg_);
956  optimizer_->addEdge(kinematics_edge);
957  }
958 }
959 
960 
962 {
963  //TODO(roesmann): Note, these edges can result in odd predictions, in particular
964  // we can observe a substantional mismatch between open- and closed-loop planning
965  // leading to a poor control performance.
966  // At the moment, we keep these functionality for oscillation recovery:
967  // Activating the edge for a short time period might not be crucial and
968  // could move the robot to a new oscillation-free state.
969  // This needs to be analyzed in more detail!
971  return; // if weight equals zero skip adding edges!
972 
974  {
975  ROS_WARN("TebOptimalPlanner::AddEdgesPreferRotDir(): unsupported RotType selected. Skipping edge creation.");
976  return;
977  }
978 
979  // create edge for satisfiying kinematic constraints
980  Eigen::Matrix<double,1,1> information_rotdir;
981  information_rotdir.fill(cfg_->optim.weight_prefer_rotdir);
982 
983  for (int i=0; i < teb_.sizePoses()-1 && i < 3; ++i) // currently: apply to first 3 rotations
984  {
985  EdgePreferRotDir* rotdir_edge = new EdgePreferRotDir;
986  rotdir_edge->setVertex(0,teb_.PoseVertex(i));
987  rotdir_edge->setVertex(1,teb_.PoseVertex(i+1));
988  rotdir_edge->setInformation(information_rotdir);
989 
991  rotdir_edge->preferLeft();
992  else if (prefer_rotdir_ == RotType::right)
993  rotdir_edge->preferRight();
994 
995  optimizer_->addEdge(rotdir_edge);
996  }
997 }
998 
1000 {
1001  Eigen::Matrix<double,2,2> information;
1002  information(0,0) = cfg_->optim.weight_velocity_obstacle_ratio;
1003  information(1,1) = cfg_->optim.weight_velocity_obstacle_ratio;
1004  information(0,1) = information(1,0) = 0;
1005 
1006  auto iter_obstacle = obstacles_per_vertex_.begin();
1007 
1008  for (int index = 0; index < teb_.sizePoses() - 1; ++index)
1009  {
1010  for (const ObstaclePtr obstacle : (*iter_obstacle++))
1011  {
1013  edge->setVertex(0,teb_.PoseVertex(index));
1014  edge->setVertex(1,teb_.PoseVertex(index + 1));
1015  edge->setVertex(2,teb_.TimeDiffVertex(index));
1016  edge->setInformation(information);
1017  edge->setParameters(*cfg_, obstacle.get());
1018  optimizer_->addEdge(edge);
1019  }
1020  }
1021 }
1022 
1023 bool TebOptimalPlanner::hasDiverged() const
1024 {
1025  // Early returns if divergence detection is not active
1027  return false;
1028 
1029  auto stats_vector = optimizer_->batchStatistics();
1030 
1031  // No statistics yet
1032  if (stats_vector.empty())
1033  return false;
1034 
1035  // Grab the statistics of the final iteration
1036  const auto last_iter_stats = stats_vector.back();
1037 
1038  return last_iter_stats.chi2 > cfg_->recovery.divergence_detection_max_chi_squared;
1039 }
1040 
1041 void TebOptimalPlanner::computeCurrentCost(double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
1042 {
1043  // check if graph is empty/exist -> important if function is called between buildGraph and optimizeGraph/clearGraph
1044  bool graph_exist_flag(false);
1045  if (optimizer_->edges().empty() && optimizer_->vertices().empty())
1046  {
1047  // here the graph is build again, for time efficiency make sure to call this function
1048  // between buildGraph and Optimize (deleted), but it depends on the application
1049  buildGraph();
1050  optimizer_->initializeOptimization();
1051  }
1052  else
1053  {
1054  graph_exist_flag = true;
1055  }
1056 
1057  optimizer_->computeInitialGuess();
1058 
1059  cost_ = 0;
1060 
1061  if (alternative_time_cost)
1062  {
1064  // TEST we use SumOfAllTimeDiffs() here, because edge cost depends on number of samples, which is not always the same for similar TEBs,
1065  // since we are using an AutoResize Function with hysteresis.
1066  }
1067 
1068  // now we need pointers to all edges -> calculate error for each edge-type
1069  // since we aren't storing edge pointers, we need to check every edge
1070  for (std::vector<g2o::OptimizableGraph::Edge*>::const_iterator it = optimizer_->activeEdges().begin(); it!= optimizer_->activeEdges().end(); it++)
1071  {
1072  double cur_cost = (*it)->chi2();
1073 
1074  if (dynamic_cast<EdgeObstacle*>(*it) != nullptr
1075  || dynamic_cast<EdgeInflatedObstacle*>(*it) != nullptr
1076  || dynamic_cast<EdgeDynamicObstacle*>(*it) != nullptr)
1077  {
1078  cur_cost *= obst_cost_scale;
1079  }
1080  else if (dynamic_cast<EdgeViaPoint*>(*it) != nullptr)
1081  {
1082  cur_cost *= viapoint_cost_scale;
1083  }
1084  else if (dynamic_cast<EdgeTimeOptimal*>(*it) != nullptr && alternative_time_cost)
1085  {
1086  continue; // skip these edges if alternative_time_cost is active
1087  }
1088  cost_ += cur_cost;
1089  }
1090 
1091  // delete temporary created graph
1092  if (!graph_exist_flag)
1093  clearGraph();
1094 }
1095 
1096 
1097 void TebOptimalPlanner::extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const
1098 {
1099  if (dt == 0)
1100  {
1101  vx = 0;
1102  vy = 0;
1103  omega = 0;
1104  return;
1105  }
1106 
1107  Eigen::Vector2d deltaS = pose2.position() - pose1.position();
1108 
1109  if (cfg_->robot.max_vel_y == 0) // nonholonomic robot
1110  {
1111  Eigen::Vector2d conf1dir( cos(pose1.theta()), sin(pose1.theta()) );
1112  // translational velocity
1113  double dir = deltaS.dot(conf1dir);
1114  vx = (double) g2o::sign(dir) * deltaS.norm()/dt;
1115  vy = 0;
1116  }
1117  else // holonomic robot
1118  {
1119  // transform pose 2 into the current robot frame (pose1)
1120  // for velocities only the rotation of the direction vector is necessary.
1121  // (map->pose1-frame: inverse 2d rotation matrix)
1122  double cos_theta1 = std::cos(pose1.theta());
1123  double sin_theta1 = std::sin(pose1.theta());
1124  double p1_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
1125  double p1_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
1126  vx = p1_dx / dt;
1127  vy = p1_dy / dt;
1128  }
1129 
1130  // rotational velocity
1131  double orientdiff = g2o::normalize_theta(pose2.theta() - pose1.theta());
1132  omega = orientdiff/dt;
1134 
1135 bool TebOptimalPlanner::getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const
1136 {
1137  if (teb_.sizePoses()<2)
1138  {
1139  ROS_ERROR("TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist.");
1140  vx = 0;
1141  vy = 0;
1142  omega = 0;
1143  return false;
1144  }
1145  look_ahead_poses = std::max(1, std::min(look_ahead_poses, teb_.sizePoses() - 1 - cfg_->trajectory.prevent_look_ahead_poses_near_goal));
1146  double dt = 0.0;
1147  for(int counter = 0; counter < look_ahead_poses; ++counter)
1148  {
1149  dt += teb_.TimeDiff(counter);
1150  if(dt >= cfg_->trajectory.dt_ref * look_ahead_poses) // TODO: change to look-ahead time? Refine trajectory?
1151  {
1152  look_ahead_poses = counter + 1;
1153  break;
1154  }
1155  }
1156  if (dt<=0)
1157  {
1158  ROS_ERROR("TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!");
1159  vx = 0;
1160  vy = 0;
1161  omega = 0;
1162  return false;
1163  }
1164 
1165  // Get velocity from the first two configurations
1166  extractVelocity(teb_.Pose(0), teb_.Pose(look_ahead_poses), dt, vx, vy, omega);
1167  return true;
1168 }
1169 
1170 void TebOptimalPlanner::getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const
1172  int n = teb_.sizePoses();
1173  velocity_profile.resize( n+1 );
1174 
1175  // start velocity
1176  velocity_profile.front().linear.z = 0;
1177  velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0;
1178  velocity_profile.front().linear.x = vel_start_.second.linear.x;
1179  velocity_profile.front().linear.y = vel_start_.second.linear.y;
1180  velocity_profile.front().angular.z = vel_start_.second.angular.z;
1181 
1182  for (int i=1; i<n; ++i)
1183  {
1184  velocity_profile[i].linear.z = 0;
1185  velocity_profile[i].angular.x = velocity_profile[i].angular.y = 0;
1186  extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), velocity_profile[i].linear.x, velocity_profile[i].linear.y, velocity_profile[i].angular.z);
1187  }
1188 
1189  // goal velocity
1190  velocity_profile.back().linear.z = 0;
1191  velocity_profile.back().angular.x = velocity_profile.back().angular.y = 0;
1192  velocity_profile.back().linear.x = vel_goal_.second.linear.x;
1193  velocity_profile.back().linear.y = vel_goal_.second.linear.y;
1194  velocity_profile.back().angular.z = vel_goal_.second.angular.z;
1195 }
1196 
1197 void TebOptimalPlanner::getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const
1198 {
1199  int n = teb_.sizePoses();
1200 
1201  trajectory.resize(n);
1202 
1203  if (n == 0)
1204  return;
1205 
1206  double curr_time = 0;
1207 
1208  // start
1209  TrajectoryPointMsg& start = trajectory.front();
1210  teb_.Pose(0).toPoseMsg(start.pose);
1211  start.velocity.linear.z = 0;
1212  start.velocity.angular.x = start.velocity.angular.y = 0;
1213  start.velocity.linear.x = vel_start_.second.linear.x;
1214  start.velocity.linear.y = vel_start_.second.linear.y;
1215  start.velocity.angular.z = vel_start_.second.angular.z;
1216  start.time_from_start.fromSec(curr_time);
1217 
1218  curr_time += teb_.TimeDiff(0);
1219 
1220  // intermediate points
1221  for (int i=1; i < n-1; ++i)
1222  {
1223  TrajectoryPointMsg& point = trajectory[i];
1224  teb_.Pose(i).toPoseMsg(point.pose);
1225  point.velocity.linear.z = 0;
1226  point.velocity.angular.x = point.velocity.angular.y = 0;
1227  double vel1_x, vel1_y, vel2_x, vel2_y, omega1, omega2;
1228  extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), vel1_x, vel1_y, omega1);
1229  extractVelocity(teb_.Pose(i), teb_.Pose(i+1), teb_.TimeDiff(i), vel2_x, vel2_y, omega2);
1230  point.velocity.linear.x = 0.5*(vel1_x+vel2_x);
1231  point.velocity.linear.y = 0.5*(vel1_y+vel2_y);
1232  point.velocity.angular.z = 0.5*(omega1+omega2);
1233  point.time_from_start.fromSec(curr_time);
1234 
1235  curr_time += teb_.TimeDiff(i);
1236  }
1237 
1238  // goal
1239  TrajectoryPointMsg& goal = trajectory.back();
1240  teb_.BackPose().toPoseMsg(goal.pose);
1241  goal.velocity.linear.z = 0;
1242  goal.velocity.angular.x = goal.velocity.angular.y = 0;
1243  goal.velocity.linear.x = vel_goal_.second.linear.x;
1244  goal.velocity.linear.y = vel_goal_.second.linear.y;
1245  goal.velocity.angular.z = vel_goal_.second.angular.z;
1246  goal.time_from_start.fromSec(curr_time);
1247 }
1248 
1249 
1250 bool TebOptimalPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
1251  double inscribed_radius, double circumscribed_radius, int look_ahead_idx, double feasibility_check_lookahead_distance)
1252 {
1253  if (look_ahead_idx < 0 || look_ahead_idx >= teb().sizePoses())
1254  look_ahead_idx = teb().sizePoses() - 1;
1255 
1256  if (feasibility_check_lookahead_distance > 0){
1257  for (int i=1; i < teb().sizePoses(); ++i){
1258  double pose_distance=std::hypot(teb().Pose(i).x()-teb().Pose(0).x(), teb().Pose(i).y()-teb().Pose(0).y());
1259  if(pose_distance > feasibility_check_lookahead_distance){
1260  look_ahead_idx = i - 1;
1261  break;
1262  }
1263  }
1264  }
1265 
1266  for (int i=0; i <= look_ahead_idx; ++i)
1267  {
1268  if ( costmap_model->footprintCost(teb().Pose(i).x(), teb().Pose(i).y(), teb().Pose(i).theta(), footprint_spec, inscribed_radius, circumscribed_radius) == -1 )
1269  {
1270  if (visualization_)
1271  {
1272  visualization_->publishInfeasibleRobotPose(teb().Pose(i), *cfg_->robot_model, footprint_spec);
1273  }
1274  return false;
1275  }
1276  // Checks if the distance between two poses is higher than the robot radius or the orientation diff is bigger than the specified threshold
1277  // and interpolates in that case.
1278  // (if obstacles are pushing two consecutive poses away, the center between two consecutive poses might coincide with the obstacle ;-)!
1279  if (i<look_ahead_idx)
1280  {
1281  double delta_rot = g2o::normalize_theta(g2o::normalize_theta(teb().Pose(i+1).theta()) -
1282  g2o::normalize_theta(teb().Pose(i).theta()));
1283  Eigen::Vector2d delta_dist = teb().Pose(i+1).position()-teb().Pose(i).position();
1284  if(fabs(delta_rot) > cfg_->trajectory.min_resolution_collision_check_angular || delta_dist.norm() > inscribed_radius)
1285  {
1286  int n_additional_samples = std::max(std::ceil(fabs(delta_rot) / cfg_->trajectory.min_resolution_collision_check_angular),
1287  std::ceil(delta_dist.norm() / inscribed_radius)) - 1;
1288  PoseSE2 intermediate_pose = teb().Pose(i);
1289  for(int step = 0; step < n_additional_samples; ++step)
1290  {
1291  intermediate_pose.position() = intermediate_pose.position() + delta_dist / (n_additional_samples + 1.0);
1292  intermediate_pose.theta() = g2o::normalize_theta(intermediate_pose.theta() +
1293  delta_rot / (n_additional_samples + 1.0));
1294  if ( costmap_model->footprintCost(intermediate_pose.x(), intermediate_pose.y(), intermediate_pose.theta(),
1295  footprint_spec, inscribed_radius, circumscribed_radius) == -1 )
1296  {
1297  if (visualization_)
1298  {
1299  visualization_->publishInfeasibleRobotPose(intermediate_pose, *cfg_->robot_model, footprint_spec);
1300  }
1301  return false;
1302  }
1303  }
1304  }
1305  }
1306  }
1307  return true;
1308 }
1309 
1310 } // namespace teb_local_planner
teb_local_planner::EdgeDynamicObstacle
Edge defining the cost function for keeping a distance from dynamic (moving) obstacles.
Definition: edge_dynamic_obstacle.h:112
edge_obstacle.h
teb_local_planner::TimedElasticBand::Pose
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
Definition: timed_elastic_band.h:192
teb_local_planner::PoseSE2::x
double & x()
Access the x-coordinate the pose.
Definition: pose_se2.h:194
teb_local_planner::TebOptimalPlanner::optimizer
boost::shared_ptr< g2o::SparseOptimizer > optimizer()
Access the internal g2o optimizer.
Definition: optimal_planner.h:409
teb_local_planner::TebOptimalPlanner::hasDiverged
bool hasDiverged() const override
Returns true if the planner has diverged.
Definition: optimal_planner.cpp:1059
teb_local_planner::TebOptimalPlanner::getVelocityProfile
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
Definition: optimal_planner.cpp:1206
teb_local_planner::TebOptimalPlanner::AddEdgesVelocity
void AddEdgesVelocity()
Add all edges (local cost functions) for limiting the translational and angular velocity.
Definition: optimal_planner.cpp:756
edge_velocity.h
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
teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_angular
double force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
Definition: teb_config.h:87
teb_local_planner::TebConfig::Obstacles::obstacle_association_cutoff_factor
double obstacle_association_cutoff_factor
See obstacle_association_force_inclusion_factor, but beyond a multiple of [value]*min_obstacle_dist a...
Definition: teb_config.h:138
teb_local_planner::TebConfig::Optimization::weight_viapoint
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
Definition: teb_config.h:175
cmd_vel_to_ackermann_drive.Twist
Twist
Definition: cmd_vel_to_ackermann_drive.py:56
teb_local_planner::EdgeAccelerationGoal
Edge defining the cost function for limiting the translational and rotational acceleration at the end...
Definition: edge_acceleration.h:423
teb_local_planner::TebConfig::Obstacles::inflation_dist
double inflation_dist
buffer zone around obstacles with non-zero penalty costs (should be larger than min_obstacle_dist in ...
Definition: teb_config.h:130
teb_local_planner::TebConfig::Optimization::weight_dynamic_obstacle
double weight_dynamic_obstacle
Optimization weight for satisfying a minimum separation from dynamic obstacles.
Definition: teb_config.h:172
teb_local_planner::cross2d
double cross2d(const V1 &v1, const V2 &v2)
Calculate the 2d cross product (returns length of the resulting vector along the z-axis in 3d)
Definition: misc.h:156
teb_local_planner::TebOptimalPlanner::vel_start_
std::pair< bool, geometry_msgs::Twist > vel_start_
Store the initial velocity at the start pose.
Definition: optimal_planner.h:723
teb_local_planner::TebOptimalPlanner::optimizeTEB
bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards=false, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Optimize a previously initialized trajectory (actual TEB optimization loop).
Definition: optimal_planner.cpp:218
teb_local_planner::EdgeVelocityHolonomic
Edge defining the cost function for limiting the translational and rotational velocity according to x...
Definition: edge_velocity.h:262
teb_local_planner::TebOptimalPlanner::cost_
double cost_
Store cost value of the current hyper-graph.
Definition: optimal_planner.h:716
boost::shared_ptr< TebVisualization >
via_points
ViaPointContainer via_points
Definition: test_optim_node.cpp:55
teb_local_planner::PoseSE2::toPoseMsg
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
Definition: pose_se2.h:239
teb_local_planner::TebConfig::Optimization::weight_prefer_rotdir
double weight_prefer_rotdir
Optimization weight for preferring a specific turning direction (-> currently only activated if an os...
Definition: teb_config.h:176
teb_local_planner::PoseSE2::y
double & y()
Access the y-coordinate the pose.
Definition: pose_se2.h:206
base_local_planner::CostmapModel::footprintCost
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
teb_local_planner::TebConfig::Optimization::weight_acc_lim_x
double weight_acc_lim_x
Optimization weight for satisfying the maximum allowed translational acceleration.
Definition: teb_config.h:162
teb_local_planner::TebConfig::Trajectory::dt_ref
double dt_ref
Desired temporal resolution of the trajectory (should be in the magniture of the underlying control r...
Definition: teb_config.h:75
teb_local_planner::TebOptimalPlanner::vel_goal_
std::pair< bool, geometry_msgs::Twist > vel_goal_
Store the final velocity at the goal pose.
Definition: optimal_planner.h:724
teb_local_planner::EdgeViaPoint
Edge defining the cost function for pushing a configuration towards a via point.
Definition: edge_via_point.h:107
teb_local_planner::TebOptimalPlanner::AddEdgesKinematicsDiffDrive
void AddEdgesKinematicsDiffDrive()
Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive rob...
Definition: optimal_planner.cpp:952
teb_local_planner::BaseTebMultiEdge::setTebConfig
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
Definition: base_teb_edges.h:296
teb_local_planner::TebOptimalPlanner::computeCurrentCost
void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Compute the cost vector of a given optimization problen (hyper-graph must exist).
Definition: optimal_planner.cpp:1077
teb_local_planner::TebOptimalPlanner::setVelocityGoal
void setVelocityGoal(const geometry_msgs::Twist &vel_goal)
Set the desired final velocity at the trajectory's goal pose.
Definition: optimal_planner.cpp:277
teb_local_planner::TebOptimalPlanner::initOptimizer
boost::shared_ptr< g2o::SparseOptimizer > initOptimizer()
Initialize and configure the g2o sparse optimizer.
Definition: optimal_planner.cpp:197
teb_local_planner::TebConfig::Trajectory::teb_autosize
double teb_autosize
Enable automatic resizing of the trajectory w.r.t to the temporal resolution (recommended)
Definition: teb_config.h:74
edge_prefer_rotdir.h
teb_local_planner::TebConfig::Trajectory::publish_feedback
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
Definition: teb_config.h:90
teb_local_planner::TebOptimalPlanner::isTrajectoryFeasible
virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0)
Check whether the planned trajectory is feasible or not.
Definition: optimal_planner.cpp:1286
teb_local_planner::TimedElasticBand::TimeDiff
double & TimeDiff(int index)
Access the time difference at pos index of the time sequence.
Definition: timed_elastic_band.h:170
teb_local_planner::TebOptimalPlanner::AddEdgesTimeOptimal
void AddEdgesTimeOptimal()
Add all edges (local cost functions) for minimizing the transition time (resp. minimize time differen...
Definition: optimal_planner.cpp:913
ROS_DEBUG_COND
#define ROS_DEBUG_COND(cond,...)
edge_kinematics.h
teb_local_planner::EdgeAccelerationGoal::setGoalVelocity
void setGoalVelocity(const geometry_msgs::Twist &vel_goal)
Set the goal / final velocity that is taken into account for calculating the acceleration.
Definition: edge_acceleration.h:484
teb_local_planner::TimedElasticBand::isInit
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences)
Definition: timed_elastic_band.h:645
teb_local_planner::Obstacle
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:103
teb_local_planner::TimedElasticBand::BackPose
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
Definition: timed_elastic_band.h:212
teb_local_planner::RotType::left
@ left
step
unsigned int step
teb_local_planner::TebConfig::Obstacles::obstacle_association_force_inclusion_factor
double obstacle_association_force_inclusion_factor
The non-legacy obstacle association technique tries to connect only relevant obstacles with the discr...
Definition: teb_config.h:137
teb_local_planner::TebOptimalPlanner::AddEdgesDynamicObstacles
void AddEdgesDynamicObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles.
Definition: optimal_planner.cpp:682
teb_local_planner::EdgeVelocityObstacleRatio::setParameters
void setParameters(const TebConfig &cfg, const Obstacle *obstacle)
Set all parameters at once.
Definition: edge_velocity_obstacle_ratio.h:178
teb_local_planner::RotType
RotType
Symbols for left/none/right rotations
Definition: misc.h:89
teb_local_planner::EdgeVelocityObstacleRatio
Edge defining the cost function for keeping a minimum distance from obstacles.
Definition: edge_velocity_obstacle_ratio.h:106
teb_local_planner::TimedElasticBand::findClosestTrajectoryPose
int findClosestTrajectoryPose(const Eigen::Ref< const Eigen::Vector2d > &ref_point, double *distance=NULL, int begin_idx=0) const
Find the closest point on the trajectory w.r.t. to a provided reference point.
Definition: timed_elastic_band.cpp:491
teb_local_planner::EdgeViaPoint::setParameters
void setParameters(const TebConfig &cfg, const Eigen::Vector2d *via_point)
Set all parameters at once.
Definition: edge_via_point.h:146
teb_local_planner::TebConfig::Optimization::no_outer_iterations
int no_outer_iterations
Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with...
Definition: teb_config.h:152
teb_local_planner::TebOptimalPlanner::AddEdgesVelocityObstacleRatio
void AddEdgesVelocityObstacleRatio()
Add all edges (local cost function) for reducing the velocity of a vertex due to its associated obsta...
Definition: optimal_planner.cpp:1035
teb_local_planner::TebOptimalPlanner::clearGraph
void clearGraph()
Clear an existing internal hyper-graph.
Definition: optimal_planner.cpp:440
teb_local_planner::TebConfig::Optimization::no_inner_iterations
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
Definition: teb_config.h:151
teb_local_planner::TebConfig::Trajectory::dt_hysteresis
double dt_hysteresis
Hysteresis for automatic resizing depending on the current temporal resolution (dt): usually 10% of d...
Definition: teb_config.h:76
edge_dynamic_obstacle.h
export_to_svg.point
list point
Definition: export_to_svg.py:223
teb_local_planner::TebConfig::Trajectory::min_resolution_collision_check_angular
double min_resolution_collision_check_angular
Definition: teb_config.h:91
edge_via_point.h
teb_local_planner::TebConfig::Optimization::weight_obstacle
double weight_obstacle
Optimization weight for satisfying a minimum separation from obstacles.
Definition: teb_config.h:170
teb_local_planner::TebOptimalPlanner::obstacles_
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
Definition: optimal_planner.h:712
teb_local_planner::TebOptimalPlanner::AddEdgesPreferRotDir
void AddEdgesPreferRotDir()
Add all edges (local cost functions) for prefering a specifiy turning direction (by penalizing the ot...
Definition: optimal_planner.cpp:997
teb_local_planner::TebConfig::recovery
struct teb_local_planner::TebConfig::Recovery recovery
Parameters related to recovery and backup strategies.
teb_local_planner::TebConfig::Optimization::weight_max_vel_x
double weight_max_vel_x
Optimization weight for satisfying the maximum allowed translational velocity.
Definition: teb_config.h:159
teb_local_planner::TebConfig::Optimization::weight_adapt_factor
double weight_adapt_factor
Some special weights (currently 'weight_obstacle') are repeatedly scaled by this factor in each outer...
Definition: teb_config.h:178
teb_local_planner::TebOptimalPlanner::setVisualization
void setVisualization(TebVisualizationPtr visualization)
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and ...
Definition: optimal_planner.cpp:143
teb_local_planner::TebConfig::Optimization::weight_inflation
double weight_inflation
Optimization weight for the inflation penalty (should be small)
Definition: teb_config.h:171
teb_local_planner::TebConfig::Optimization::weight_velocity_obstacle_ratio
double weight_velocity_obstacle_ratio
Optimization weight for satisfying a maximum allowed velocity with respect to the distance to a stati...
Definition: teb_config.h:174
base_local_planner::CostmapModel
teb_local_planner::TebOptimalPlanner::getVelocityCommand
virtual bool getVelocityCommand(double &vx, double &vy, double &omega, int look_ahead_poses) const
Get the velocity command from a previously optimized plan to control the robot at the current samplin...
Definition: optimal_planner.cpp:1171
teb_local_planner::TebOptimalPlanner::AddTEBVertices
void AddTEBVertices()
Add all relevant vertices to the hyper-graph as optimizable variables.
Definition: optimal_planner.cpp:458
teb_local_planner::TebOptimalPlanner::visualization_
TebVisualizationPtr visualization_
Instance of the visualization class.
Definition: optimal_planner.h:720
teb_local_planner::TimedElasticBand::updateAndPruneTEB
void updateAndPruneTEB(boost::optional< const PoseSE2 & > new_start, boost::optional< const PoseSE2 & > new_goal, int min_samples=3)
Hot-Start from an existing trajectory with updated start and goal poses.
Definition: timed_elastic_band.cpp:591
ROS_DEBUG
#define ROS_DEBUG(...)
visual
TebVisualizationPtr visual
Definition: test_optim_node.cpp:53
teb_local_planner::TebOptimalPlanner::initialized_
bool initialized_
Keeps track about the correct initialization of this class.
Definition: optimal_planner.h:726
visualize_velocity_profile.trajectory
list trajectory
Definition: visualize_velocity_profile.py:72
teb_local_planner::TebOptimalPlanner::~TebOptimalPlanner
virtual ~TebOptimalPlanner()
Destruct the optimal planner.
Definition: optimal_planner.cpp:108
teb_local_planner::TebOptimalPlanner::visualize
virtual void visualize()
Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz).
Definition: optimal_planner.cpp:148
teb_local_planner::TebConfig::trajectory
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
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::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::ObstContainer
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:333
teb_local_planner::EdgeObstacle
Edge defining the cost function for keeping a minimum distance from obstacles.
Definition: edge_obstacle.h:111
teb_local_planner::PoseSE2::position
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:181
teb_local_planner::TebConfig::Trajectory::max_samples
int max_samples
Maximum number of samples; Warning: if too small the discretization/resolution might not be sufficien...
Definition: teb_config.h:78
edge_shortest_path.h
teb_local_planner::TebConfig::robot
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
teb_local_planner::EdgePreferRotDir
Edge defining the cost function for penalzing a specified turning direction, in particular left resp....
Definition: edge_prefer_rotdir.h:106
teb_local_planner::RotType::none
@ none
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
teb_local_planner::TEBBlockSolver
g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1 > > TEBBlockSolver
Typedef for the block solver utilized for optimization.
Definition: optimal_planner.h:111
teb_local_planner::TebOptimalPlanner::extractVelocity
void extractVelocity(const PoseSE2 &pose1, const PoseSE2 &pose2, double dt, double &vx, double &vy, double &omega) const
Extract the velocity from consecutive poses and a time difference (including strafing velocity for ho...
Definition: optimal_planner.cpp:1133
teb_local_planner::TebOptimalPlanner::AddEdgesViaPoints
void AddEdgesViaPoints()
Add all edges (local cost functions) related to minimizing the distance to via-points.
Definition: optimal_planner.cpp:711
teb_local_planner::TebOptimalPlanner::obstacles_per_vertex_
std::vector< ObstContainer > obstacles_per_vertex_
Store the obstacles associated with the n-1 initial vertices.
Definition: optimal_planner.h:714
ROS_WARN
#define ROS_WARN(...)
teb_local_planner::TimedElasticBand::PoseVertex
VertexPose * PoseVertex(int index)
Access the vertex of a pose at pos index for optimization purposes.
Definition: timed_elastic_band.h:234
teb_local_planner::BaseTebBinaryEdge::setTebConfig
void setTebConfig(const TebConfig &cfg)
Assign the TebConfig class for parameters.
Definition: base_teb_edges.h:218
teb_local_planner::TimedElasticBand::sizePoses
int sizePoses() const
Get the length of the internal pose sequence.
Definition: timed_elastic_band.h:635
edge_time_optimal.h
export_to_svg.vertices
list vertices
Definition: export_to_svg.py:233
teb_local_planner::TebVisualizationPtr
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
Definition: visualization.h:311
teb_local_planner::TebOptimalPlanner::buildGraph
bool buildGraph(double weight_multiplier=1.0)
Build the hyper-graph representing the TEB optimization problem.
Definition: optimal_planner.cpp:359
teb_local_planner::TebOptimalPlanner::teb_
TimedElasticBand teb_
Actual trajectory object.
Definition: optimal_planner.h:721
edge_acceleration.h
tf::Transform
teb_local_planner::TebOptimalPlanner::initialize
void initialize(const TebConfig &cfg, ObstContainer *obstacles=NULL, TebVisualizationPtr visual=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL)
Initializes the optimal planner.
Definition: optimal_planner.cpp:118
teb_local_planner::TebOptimalPlanner::via_points_
const ViaPointContainer * via_points_
Store via points for planning.
Definition: optimal_planner.h:713
teb_local_planner::EdgeObstacle::setParameters
void setParameters(const TebConfig &cfg, const Obstacle *obstacle)
Set all parameters at once.
Definition: edge_obstacle.h:208
teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_dist
double force_reinit_new_goal_dist
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specifie...
Definition: teb_config.h:86
teb_local_planner::TebOptimalPlanner::prefer_rotdir_
RotType prefer_rotdir_
Store whether to prefer a specific initial rotation in optimization (might be activated in case the r...
Definition: optimal_planner.h:717
teb_local_planner::TebConfig::Trajectory::via_points_ordered
bool via_points_ordered
If true, the planner adheres to the order of via-points in the storage container.
Definition: teb_config.h:82
teb_local_planner::TebConfig::Trajectory::allow_init_with_backwards_motion
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
Definition: teb_config.h:80
teb_local_planner::TebConfig::Optimization::weight_optimaltime
double weight_optimaltime
Optimization weight for contracting the trajectory w.r.t. transition time.
Definition: teb_config.h:168
teb_local_planner::TebOptimalPlanner::registerG2OTypes
static void registerG2OTypes()
Register the vertices and edges defined for the TEB to the g2o::Factory.
Definition: optimal_planner.cpp:167
start
ROSCPP_DECL void start()
teb_local_planner::TimedElasticBand::initTrajectoryToGoal
bool initTrajectoryToGoal(const PoseSE2 &start, const PoseSE2 &goal, double diststep=0, double max_vel_x=0.5, int min_samples=3, bool guess_backwards_motion=false)
Initialize a trajectory between a given start and goal pose.
Definition: timed_elastic_band.cpp:361
teb_local_planner::EdgeInflatedObstacle::setParameters
void setParameters(const TebConfig &cfg, const Obstacle *obstacle)
Set all parameters at once.
Definition: edge_obstacle.h:290
teb_local_planner::EdgePreferRotDir::preferLeft
void preferLeft()
Definition: edge_prefer_rotdir.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::PoseSE2::orientationUnitVec
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:251
teb_local_planner::TebOptimalPlanner::TebOptimalPlanner
TebOptimalPlanner()
Default constructor.
Definition: optimal_planner.cpp:98
teb_local_planner::TebOptimalPlanner::setVelocityGoalFree
void setVelocityGoalFree()
Set the desired final velocity at the trajectory's goal pose to be the maximum velocity limit.
Definition: optimal_planner.h:296
teb_local_planner::TebConfig::Trajectory::min_samples
int min_samples
Minimum number of samples (should be always greater than 2)
Definition: teb_config.h:77
teb_local_planner::TebConfig::Optimization::weight_acc_lim_y
double weight_acc_lim_y
Optimization weight for satisfying the maximum allowed strafing acceleration (in use only for holonom...
Definition: teb_config.h:163
teb_local_planner::TebConfig::Optimization::weight_max_vel_y
double weight_max_vel_y
Optimization weight for satisfying the maximum allowed strafing velocity (in use only for holonomic r...
Definition: teb_config.h:160
teb_local_planner::TebConfig::Optimization::weight_shortest_path
double weight_shortest_path
Optimization weight for contracting the trajectory w.r.t. path length.
Definition: teb_config.h:169
teb_local_planner::TebConfig::Recovery::divergence_detection_enable
bool divergence_detection_enable
True to enable divergence detection.
Definition: teb_config.h:227
teb_local_planner::TimedElasticBand::sizeTimeDiffs
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
Definition: timed_elastic_band.h:640
ROS_ERROR
#define ROS_ERROR(...)
teb_local_planner::TebConfig::Optimization::weight_dynamic_obstacle_inflation
double weight_dynamic_obstacle_inflation
Optimization weight for the inflation penalty of dynamic obstacles (should be small)
Definition: teb_config.h:173
teb_local_planner::TebOptimalPlanner::AddEdgesObstaclesLegacy
void AddEdgesObstaclesLegacy(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles (legacy asso...
Definition: optimal_planner.cpp:587
teb_local_planner::TebConfig::Recovery::divergence_detection_max_chi_squared
int divergence_detection_max_chi_squared
Maximum acceptable Mahalanobis distance above which it is assumed that the optimization diverged.
Definition: teb_config.h:228
teb_local_planner::TebConfig::Optimization::weight_max_vel_theta
double weight_max_vel_theta
Optimization weight for satisfying the maximum allowed angular velocity.
Definition: teb_config.h:161
teb_local_planner::TebOptimalPlanner::optimizer_
boost::shared_ptr< g2o::SparseOptimizer > optimizer_
g2o optimizer for trajectory optimization
Definition: optimal_planner.h:722
teb_local_planner::TebConfig::robot_model
RobotFootprintModelPtr robot_model
model of the robot's footprint
Definition: teb_config.h:69
teb_local_planner::TebOptimalPlanner::AddEdgesKinematicsCarlike
void AddEdgesKinematicsCarlike()
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot.
Definition: optimal_planner.cpp:974
teb_local_planner::TebConfig::Obstacles::include_dynamic_obstacles
bool include_dynamic_obstacles
Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (t...
Definition: teb_config.h:132
teb_local_planner::TebOptimalPlanner::optimizeGraph
bool optimizeGraph(int no_iterations, bool clear_after=true)
Optimize the previously constructed hyper-graph to deform / optimize the TEB.
Definition: optimal_planner.cpp:404
teb_local_planner::EdgePreferRotDir::preferRight
void preferRight()
Definition: edge_prefer_rotdir.h:141
teb_local_planner::TEBLinearSolver
g2o::LinearSolverCSparse< TEBBlockSolver::PoseMatrixType > TEBLinearSolver
Typedef for the linear solver utilized for optimization.
Definition: optimal_planner.h:114
teb_local_planner::TebOptimalPlanner::getFullTrajectory
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
Definition: optimal_planner.cpp:1233
teb_local_planner::TebOptimalPlanner::AddEdgesShortestPath
void AddEdgesShortestPath()
Add all edges (local cost functions) for minimizing the path length.
Definition: optimal_planner.cpp:931
teb_local_planner::TebOptimalPlanner::teb
TimedElasticBand & teb()
Access the internal TimedElasticBand trajectory.
Definition: optimal_planner.h:396
teb_local_planner::TebConfig::Optimization::weight_kinematics_forward_drive
double weight_kinematics_forward_drive
Optimization weight for forcing the robot to choose only forward directions (positive transl....
Definition: teb_config.h:166
teb_local_planner::TebConfig::Robot::acc_lim_y
double acc_lim_y
Maximum strafing acceleration of the robot.
Definition: teb_config.h:105
optimal_planner.h
teb_local_planner::EdgeInflatedObstacle
Edge defining the cost function for keeping a minimum distance from inflated obstacles.
Definition: edge_obstacle.h:233
edge_velocity_obstacle_ratio.h
teb_local_planner::TebOptimalPlanner::AddEdgesAcceleration
void AddEdgesAcceleration()
Add all edges (local cost functions) for limiting the translational and angular acceleration.
Definition: optimal_planner.cpp:807
teb_local_planner::TebConfig::Optimization::weight_kinematics_turning_radius
double weight_kinematics_turning_radius
Optimization weight for enforcing a minimum turning radius (carlike robots)
Definition: teb_config.h:167
teb_local_planner::TebOptimalPlanner::optimized_
bool optimized_
This variable is true as long as the last optimization has been completed successful.
Definition: optimal_planner.h:727
teb_local_planner::TebOptimalPlanner::cfg_
const TebConfig * cfg_
Config class that stores and manages all related parameters.
Definition: optimal_planner.h:711
teb_local_planner::TebConfig::Optimization::weight_acc_lim_theta
double weight_acc_lim_theta
Optimization weight for satisfying the maximum allowed angular acceleration.
Definition: teb_config.h:164
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
teb_local_planner::TebConfig::Obstacles::legacy_obstacle_association
bool legacy_obstacle_association
If true, the old association strategy is used (for each obstacle, find the nearest TEB pose),...
Definition: teb_config.h:136
teb_local_planner::ViaPointContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
Definition: optimal_planner.h:118
teb_local_planner::TebConfig::Optimization::optimization_activate
bool optimization_activate
Activate the optimization.
Definition: teb_config.h:154
teb_local_planner::TebConfig::Optimization::optimization_verbose
bool optimization_verbose
Print verbose information.
Definition: teb_config.h:155
teb_local_planner::TebConfig::Optimization::weight_kinematics_nh
double weight_kinematics_nh
Optimization weight for satisfying the non-holonomic kinematics.
Definition: teb_config.h:165
teb_local_planner::TimedElasticBand::clearTimedElasticBand
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
Definition: timed_elastic_band.cpp:238
teb_local_planner::TebConfig::optim
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
teb_local_planner::TebOptimalPlanner::setVelocityStart
void setVelocityStart(const geometry_msgs::Twist &vel_start)
Set the initial velocity at the trajectory's start pose (e.g. the robot's velocity) [twist overload].
Definition: optimal_planner.cpp:269
teb_local_planner::TebConfig::Robot::max_vel_theta
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:103
teb_local_planner::TebConfig::Obstacles::obstacle_poses_affected
int obstacle_poses_affected
The obstacle position is attached to the closest pose on the trajectory to reduce computational effor...
Definition: teb_config.h:135
teb_local_planner::TimedElasticBand::autoResize
void autoResize(double dt_ref, double dt_hysteresis, int min_samples=3, int max_samples=1000, bool fast_mode=false)
Resize the trajectory by removing or inserting a (pose,dt) pair depending on a reference temporal res...
Definition: timed_elastic_band.cpp:263
teb_local_planner::EdgeKinematicsDiffDrive
Edge defining the cost function for satisfying the non-holonomic kinematics of a differential drive m...
Definition: edge_kinematics.h:114
teb_local_planner::RotType::right
@ right
teb_local_planner::TebConfig::Trajectory::prevent_look_ahead_poses_near_goal
int prevent_look_ahead_poses_near_goal
Index of the pose used to extract the velocity command.
Definition: teb_config.h:93
teb_local_planner::TebOptimalPlanner::plan
virtual bool plan(const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false)
Plan a trajectory based on an initial reference plan.
Definition: optimal_planner.cpp:283
teb_local_planner::TimedElasticBand::TimeDiffVertex
VertexTimeDiff * TimeDiffVertex(int index)
Access the vertex of a time difference at pos index for optimization purposes.
Definition: timed_elastic_band.h:245
teb_local_planner::TimedElasticBand::getSumOfAllTimeDiffs
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence)
Definition: timed_elastic_band.cpp:325
teb_local_planner::TebOptimalPlanner::AddEdgesObstacles
void AddEdgesObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles.
Definition: optimal_planner.cpp:480


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