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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 1 2022 02:26:31