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 #include <map>
41 #include <limits>
42 
43 
44 namespace teb_local_planner
45 {
46 
47 // ============== Implementation ===================
48 
49 TebOptimalPlanner::TebOptimalPlanner() : cfg_(NULL), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), prefer_rotdir_(RotType::none),
50  robot_model_(new PointRobotFootprint()), initialized_(false), optimized_(false)
51 {
52 }
53 
55 {
56  initialize(cfg, obstacles, robot_model, visual, via_points);
57 }
58 
60 {
61  clearGraph();
62  // free dynamically allocated memory
63  //if (optimizer_)
64  // g2o::Factory::destroy();
65  //g2o::OptimizationAlgorithmFactory::destroy();
66  //g2o::HyperGraphActionLibrary::destroy();
67 }
68 
70 {
71  // init optimizer (set solver and block ordering settings)
73 
74  cfg_ = &cfg;
75  obstacles_ = obstacles;
76  robot_model_ = robot_model;
78  cost_ = HUGE_VAL;
80  setVisualization(visual);
81 
82  vel_start_.first = true;
83  vel_start_.second.linear.x = 0;
84  vel_start_.second.linear.y = 0;
85  vel_start_.second.angular.z = 0;
86 
87  vel_goal_.first = true;
88  vel_goal_.second.linear.x = 0;
89  vel_goal_.second.linear.y = 0;
90  vel_goal_.second.angular.z = 0;
91  initialized_ = true;
92 }
93 
94 
96 {
97  visualization_ = visualization;
98 }
99 
101 {
102  if (!visualization_)
103  return;
104 
105  visualization_->publishLocalPlanAndPoses(teb_);
106 
107  if (teb_.sizePoses() > 0)
108  visualization_->publishRobotFootprintModel(teb_.Pose(0), *robot_model_);
109 
111  visualization_->publishFeedbackMessage(*this, *obstacles_);
112 
113 }
114 
115 
116 /*
117  * registers custom vertices and edges in g2o framework
118  */
120 {
121  g2o::Factory* factory = g2o::Factory::instance();
122  factory->registerType("VERTEX_POSE", new g2o::HyperGraphElementCreator<VertexPose>);
123  factory->registerType("VERTEX_TIMEDIFF", new g2o::HyperGraphElementCreator<VertexTimeDiff>);
124 
125  factory->registerType("EDGE_TIME_OPTIMAL", new g2o::HyperGraphElementCreator<EdgeTimeOptimal>);
126  factory->registerType("EDGE_SHORTEST_PATH", new g2o::HyperGraphElementCreator<EdgeShortestPath>);
127  factory->registerType("EDGE_VELOCITY", new g2o::HyperGraphElementCreator<EdgeVelocity>);
128  factory->registerType("EDGE_VELOCITY_HOLONOMIC", new g2o::HyperGraphElementCreator<EdgeVelocityHolonomic>);
129  factory->registerType("EDGE_ACCELERATION", new g2o::HyperGraphElementCreator<EdgeAcceleration>);
130  factory->registerType("EDGE_ACCELERATION_START", new g2o::HyperGraphElementCreator<EdgeAccelerationStart>);
131  factory->registerType("EDGE_ACCELERATION_GOAL", new g2o::HyperGraphElementCreator<EdgeAccelerationGoal>);
132  factory->registerType("EDGE_ACCELERATION_HOLONOMIC", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomic>);
133  factory->registerType("EDGE_ACCELERATION_HOLONOMIC_START", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicStart>);
134  factory->registerType("EDGE_ACCELERATION_HOLONOMIC_GOAL", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicGoal>);
135  factory->registerType("EDGE_KINEMATICS_DIFF_DRIVE", new g2o::HyperGraphElementCreator<EdgeKinematicsDiffDrive>);
136  factory->registerType("EDGE_KINEMATICS_CARLIKE", new g2o::HyperGraphElementCreator<EdgeKinematicsCarlike>);
137  factory->registerType("EDGE_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeObstacle>);
138  factory->registerType("EDGE_INFLATED_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeInflatedObstacle>);
139  factory->registerType("EDGE_DYNAMIC_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeDynamicObstacle>);
140  factory->registerType("EDGE_VIA_POINT", new g2o::HyperGraphElementCreator<EdgeViaPoint>);
141  factory->registerType("EDGE_PREFER_ROTDIR", new g2o::HyperGraphElementCreator<EdgePreferRotDir>);
142  return;
143 }
144 
145 /*
146  * initialize g2o optimizer. Set solver settings here.
147  * Return: pointer to new SparseOptimizer Object.
148  */
150 {
151  // Call register_g2o_types once, even for multiple TebOptimalPlanner instances (thread-safe)
152  static boost::once_flag flag = BOOST_ONCE_INIT;
153  boost::call_once(&registerG2OTypes, flag);
154 
155  // allocating the optimizer
156  boost::shared_ptr<g2o::SparseOptimizer> optimizer = boost::make_shared<g2o::SparseOptimizer>();
157  TEBLinearSolver* linearSolver = new TEBLinearSolver(); // see typedef in optimization.h
158  linearSolver->setBlockOrdering(true);
159  TEBBlockSolver* blockSolver = new TEBBlockSolver(linearSolver);
160  g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(blockSolver);
161 
162  optimizer->setAlgorithm(solver);
163 
164  optimizer->initMultiThreading(); // required for >Eigen 3.1
165 
166  return optimizer;
167 }
168 
169 
170 bool TebOptimalPlanner::optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards,
171  double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
172 {
173  if (cfg_->optim.optimization_activate==false)
174  return false;
175 
176  bool success = false;
177  optimized_ = false;
178 
179  double weight_multiplier = 1.0;
180 
181  // TODO(roesmann): we introduced the non-fast mode with the support of dynamic obstacles
182  // (which leads to better results in terms of x-y-t homotopy planning).
183  // however, we have not tested this mode intensively yet, so we keep
184  // the legacy fast mode as default until we finish our tests.
185  bool fast_mode = !cfg_->obstacles.include_dynamic_obstacles;
186 
187  for(int i=0; i<iterations_outerloop; ++i)
188  {
190  {
191  //teb_.autoResize(cfg_->trajectory.dt_ref, cfg_->trajectory.dt_hysteresis, cfg_->trajectory.min_samples, cfg_->trajectory.max_samples);
193 
194  }
195 
196  success = buildGraph(weight_multiplier);
197  if (!success)
198  {
199  clearGraph();
200  return false;
201  }
202  success = optimizeGraph(iterations_innerloop, false);
203  if (!success)
204  {
205  clearGraph();
206  return false;
207  }
208  optimized_ = true;
209 
210  if (compute_cost_afterwards && i==iterations_outerloop-1) // compute cost vec only in the last iteration
211  computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
212 
213  clearGraph();
214 
215  weight_multiplier *= cfg_->optim.weight_adapt_factor;
216  }
217 
218  return true;
219 }
220 
222 {
223  vel_start_.first = true;
224  vel_start_.second.linear.x = vel_start.linear.x;
225  vel_start_.second.linear.y = vel_start.linear.y;
226  vel_start_.second.angular.z = vel_start.angular.z;
227 }
228 
230 {
231  vel_goal_.first = true;
232  vel_goal_.second = vel_goal;
233 }
234 
235 bool TebOptimalPlanner::plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
236 {
237  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
238  if (!teb_.isInit())
239  {
240  // init trajectory
242  }
243  else // warm start
244  {
245  PoseSE2 start_(initial_plan.front().pose);
246  PoseSE2 goal_(initial_plan.back().pose);
247  if (teb_.sizePoses()>0
248  && (goal_.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist
249  && fabs(g2o::normalize_theta(goal_.theta() - teb_.BackPose().theta())) < cfg_->trajectory.force_reinit_new_goal_angular) // actual warm start!
250  teb_.updateAndPruneTEB(start_, goal_, cfg_->trajectory.min_samples); // update TEB
251  else // goal too far away -> reinit
252  {
253  ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
256  }
257  }
258  if (start_vel)
259  setVelocityStart(*start_vel);
260  if (free_goal_vel)
262  else
263  vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified)
264 
265  // now optimize
267 }
268 
269 
270 bool TebOptimalPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
271 {
272  PoseSE2 start_(start);
273  PoseSE2 goal_(goal);
274  return plan(start_, goal_, start_vel);
275 }
276 
277 bool TebOptimalPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
278 {
279  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
280  if (!teb_.isInit())
281  {
282  // init trajectory
283  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
284  }
285  else // warm start
286  {
287  if (teb_.sizePoses() > 0
289  && fabs(g2o::normalize_theta(goal.theta() - teb_.BackPose().theta())) < cfg_->trajectory.force_reinit_new_goal_angular) // actual warm start!
291  else // goal too far away -> reinit
292  {
293  ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
296  }
297  }
298  if (start_vel)
299  setVelocityStart(*start_vel);
300  if (free_goal_vel)
302  else
303  vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified)
304 
305  // now optimize
307 }
308 
309 
310 bool TebOptimalPlanner::buildGraph(double weight_multiplier)
311 {
312  if (!optimizer_->edges().empty() || !optimizer_->vertices().empty())
313  {
314  ROS_WARN("Cannot build graph, because it is not empty. Call graphClear()!");
315  return false;
316  }
317 
318  // add TEB vertices
319  AddTEBVertices();
320 
321  // add Edges (local cost functions)
323  AddEdgesObstaclesLegacy(weight_multiplier);
324  else
325  AddEdgesObstacles(weight_multiplier);
326 
329 
331 
333 
335 
337 
339 
341  AddEdgesKinematicsDiffDrive(); // we have a differential drive robot
342  else
343  AddEdgesKinematicsCarlike(); // we have a carlike robot since the turning radius is bounded from below.
344 
345 
347 
348  return true;
349 }
350 
351 bool TebOptimalPlanner::optimizeGraph(int no_iterations,bool clear_after)
352 {
353  if (cfg_->robot.max_vel_x<0.01)
354  {
355  ROS_WARN("optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted...");
356  if (clear_after) clearGraph();
357  return false;
358  }
359 
361  {
362  ROS_WARN("optimizeGraph(): TEB is empty or has too less elements. Skipping optimization.");
363  if (clear_after) clearGraph();
364  return false;
365  }
366 
368  optimizer_->initializeOptimization();
369 
370  int iter = optimizer_->optimize(no_iterations);
371 
372  // Save Hessian for visualization
373  // g2o::OptimizationAlgorithmLevenberg* lm = dynamic_cast<g2o::OptimizationAlgorithmLevenberg*> (optimizer_->solver());
374  // lm->solver()->saveHessian("~/MasterThesis/Matlab/Hessian.txt");
375 
376  if(!iter)
377  {
378  ROS_ERROR("optimizeGraph(): Optimization failed! iter=%i", iter);
379  return false;
380  }
381 
382  if (clear_after) clearGraph();
383 
384  return true;
385 }
386 
388 {
389  // clear optimizer states
390  if (optimizer_)
391  {
392  //optimizer.edges().clear(); // optimizer.clear deletes edges!!! Therefore do not run optimizer.edges().clear()
393  optimizer_->vertices().clear(); // neccessary, because optimizer->clear deletes pointer-targets (therefore it deletes TEB states!)
394  optimizer_->clear();
395  }
396 }
397 
398 
399 
401 {
402  // add vertices to graph
403  ROS_DEBUG_COND(cfg_->optim.optimization_verbose, "Adding TEB vertices ...");
404  unsigned int id_counter = 0; // used for vertices ids
405  for (int i=0; i<teb_.sizePoses(); ++i)
406  {
407  teb_.PoseVertex(i)->setId(id_counter++);
408  optimizer_->addVertex(teb_.PoseVertex(i));
409  if (teb_.sizeTimeDiffs()!=0 && i<teb_.sizeTimeDiffs())
410  {
411  teb_.TimeDiffVertex(i)->setId(id_counter++);
412  optimizer_->addVertex(teb_.TimeDiffVertex(i));
413  }
414  }
415 }
416 
417 
418 void TebOptimalPlanner::AddEdgesObstacles(double weight_multiplier)
419 {
420  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr )
421  return; // if weight equals zero skip adding edges!
422 
423 
425 
426  Eigen::Matrix<double,1,1> information;
427  information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
428 
429  Eigen::Matrix<double,2,2> information_inflated;
430  information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
431  information_inflated(1,1) = cfg_->optim.weight_inflation;
432  information_inflated(0,1) = information_inflated(1,0) = 0;
433 
434  // iterate all teb points (skip first and last)
435  for (int i=1; i < teb_.sizePoses()-1; ++i)
436  {
437  double left_min_dist = std::numeric_limits<double>::max();
438  double right_min_dist = std::numeric_limits<double>::max();
439  Obstacle* left_obstacle = nullptr;
440  Obstacle* right_obstacle = nullptr;
441 
442  std::vector<Obstacle*> relevant_obstacles;
443 
444  const Eigen::Vector2d pose_orient = teb_.Pose(i).orientationUnitVec();
445 
446  // iterate obstacles
447  for (const ObstaclePtr& obst : *obstacles_)
448  {
449  // we handle dynamic obstacles differently below
450  if(cfg_->obstacles.include_dynamic_obstacles && obst->isDynamic())
451  continue;
452 
453  // calculate distance to robot model
454  double dist = robot_model_->calculateDistance(teb_.Pose(i), obst.get());
455 
456  // force considering obstacle if really close to the current pose
457  if (dist < cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_force_inclusion_factor)
458  {
459  relevant_obstacles.push_back(obst.get());
460  continue;
461  }
462  // cut-off distance
464  continue;
465 
466  // determine side (left or right) and assign obstacle if closer than the previous one
467  if (cross2d(pose_orient, obst->getCentroid()) > 0) // left
468  {
469  if (dist < left_min_dist)
470  {
471  left_min_dist = dist;
472  left_obstacle = obst.get();
473  }
474  }
475  else
476  {
477  if (dist < right_min_dist)
478  {
479  right_min_dist = dist;
480  right_obstacle = obst.get();
481  }
482  }
483  }
484 
485  // create obstacle edges
486  if (left_obstacle)
487  {
488  if (inflated)
489  {
490  EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
491  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
492  dist_bandpt_obst->setInformation(information_inflated);
493  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), left_obstacle);
494  optimizer_->addEdge(dist_bandpt_obst);
495  }
496  else
497  {
498  EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
499  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
500  dist_bandpt_obst->setInformation(information);
501  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), left_obstacle);
502  optimizer_->addEdge(dist_bandpt_obst);
503  }
504  }
505 
506  if (right_obstacle)
507  {
508  if (inflated)
509  {
510  EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
511  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
512  dist_bandpt_obst->setInformation(information_inflated);
513  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), right_obstacle);
514  optimizer_->addEdge(dist_bandpt_obst);
515  }
516  else
517  {
518  EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
519  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
520  dist_bandpt_obst->setInformation(information);
521  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), right_obstacle);
522  optimizer_->addEdge(dist_bandpt_obst);
523  }
524  }
525 
526  for (const Obstacle* obst : relevant_obstacles)
527  {
528  if (inflated)
529  {
530  EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
531  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
532  dist_bandpt_obst->setInformation(information_inflated);
533  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst);
534  optimizer_->addEdge(dist_bandpt_obst);
535  }
536  else
537  {
538  EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
539  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
540  dist_bandpt_obst->setInformation(information);
541  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst);
542  optimizer_->addEdge(dist_bandpt_obst);
543  }
544  }
545  }
546 
547 }
548 
549 
550 void TebOptimalPlanner::AddEdgesObstaclesLegacy(double weight_multiplier)
551 {
552  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr)
553  return; // if weight equals zero skip adding edges!
554 
555  Eigen::Matrix<double,1,1> information;
556  information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
557 
558  Eigen::Matrix<double,2,2> information_inflated;
559  information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
560  information_inflated(1,1) = cfg_->optim.weight_inflation;
561  information_inflated(0,1) = information_inflated(1,0) = 0;
562 
564 
565  for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
566  {
567  if (cfg_->obstacles.include_dynamic_obstacles && (*obst)->isDynamic()) // we handle dynamic obstacles differently below
568  continue;
569 
570  int index;
571 
573  index = teb_.sizePoses() / 2;
574  else
575  index = teb_.findClosestTrajectoryPose(*(obst->get()));
576 
577 
578  // check if obstacle is outside index-range between start and goal
579  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
580  continue;
581 
582  if (inflated)
583  {
584  EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
585  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
586  dist_bandpt_obst->setInformation(information_inflated);
587  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
588  optimizer_->addEdge(dist_bandpt_obst);
589  }
590  else
591  {
592  EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
593  dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
594  dist_bandpt_obst->setInformation(information);
595  dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
596  optimizer_->addEdge(dist_bandpt_obst);
597  }
598 
599  for (int neighbourIdx=0; neighbourIdx < floor(cfg_->obstacles.obstacle_poses_affected/2); neighbourIdx++)
600  {
601  if (index+neighbourIdx < teb_.sizePoses())
602  {
603  if (inflated)
604  {
605  EdgeInflatedObstacle* dist_bandpt_obst_n_r = new EdgeInflatedObstacle;
606  dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
607  dist_bandpt_obst_n_r->setInformation(information_inflated);
608  dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
609  optimizer_->addEdge(dist_bandpt_obst_n_r);
610  }
611  else
612  {
613  EdgeObstacle* dist_bandpt_obst_n_r = new EdgeObstacle;
614  dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
615  dist_bandpt_obst_n_r->setInformation(information);
616  dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
617  optimizer_->addEdge(dist_bandpt_obst_n_r);
618  }
619  }
620  if ( index - neighbourIdx >= 0) // needs to be casted to int to allow negative values
621  {
622  if (inflated)
623  {
624  EdgeInflatedObstacle* dist_bandpt_obst_n_l = new EdgeInflatedObstacle;
625  dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
626  dist_bandpt_obst_n_l->setInformation(information_inflated);
627  dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
628  optimizer_->addEdge(dist_bandpt_obst_n_l);
629  }
630  else
631  {
632  EdgeObstacle* dist_bandpt_obst_n_l = new EdgeObstacle;
633  dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
634  dist_bandpt_obst_n_l->setInformation(information);
635  dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
636  optimizer_->addEdge(dist_bandpt_obst_n_l);
637  }
638  }
639  }
640 
641  }
642 }
643 
644 
645 void TebOptimalPlanner::AddEdgesDynamicObstacles(double weight_multiplier)
646 {
647  if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==NULL )
648  return; // if weight equals zero skip adding edges!
649 
650  Eigen::Matrix<double,2,2> information;
651  information(0,0) = cfg_->optim.weight_dynamic_obstacle * weight_multiplier;
652  information(1,1) = cfg_->optim.weight_dynamic_obstacle_inflation;
653  information(0,1) = information(1,0) = 0;
654 
655  for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
656  {
657  if (!(*obst)->isDynamic())
658  continue;
659 
660  // Skip first and last pose, as they are fixed
661  double time = teb_.TimeDiff(0);
662  for (int i=1; i < teb_.sizePoses() - 1; ++i)
663  {
664  EdgeDynamicObstacle* dynobst_edge = new EdgeDynamicObstacle(time);
665  dynobst_edge->setVertex(0,teb_.PoseVertex(i));
666  dynobst_edge->setInformation(information);
667  dynobst_edge->setParameters(*cfg_, robot_model_.get(), obst->get());
668  optimizer_->addEdge(dynobst_edge);
669  time += teb_.TimeDiff(i); // we do not need to check the time diff bounds, since we iterate to "< sizePoses()-1".
670  }
671  }
672 }
673 
675 {
676  if (cfg_->optim.weight_viapoint==0 || via_points_==NULL || via_points_->empty() )
677  return; // if weight equals zero skip adding edges!
678 
679  int start_pose_idx = 0;
680 
681  int n = teb_.sizePoses();
682  if (n<3) // we do not have any degrees of freedom for reaching via-points
683  return;
684 
685  for (ViaPointContainer::const_iterator vp_it = via_points_->begin(); vp_it != via_points_->end(); ++vp_it)
686  {
687 
688  int index = teb_.findClosestTrajectoryPose(*vp_it, NULL, start_pose_idx);
690  start_pose_idx = index+2; // skip a point to have a DOF inbetween for further via-points
691 
692  // check if point conicides with goal or is located behind it
693  if ( index > n-2 )
694  index = n-2; // set to a pose before the goal, since we can move it away!
695  // check if point coincides with start or is located before it
696  if ( index < 1)
697  {
699  {
700  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.
701  }
702  else
703  {
704  ROS_DEBUG("TebOptimalPlanner::AddEdgesViaPoints(): skipping a via-point that is close or behind the current robot pose.");
705  continue; // skip via points really close or behind the current robot pose
706  }
707  }
708  Eigen::Matrix<double,1,1> information;
709  information.fill(cfg_->optim.weight_viapoint);
710 
711  EdgeViaPoint* edge_viapoint = new EdgeViaPoint;
712  edge_viapoint->setVertex(0,teb_.PoseVertex(index));
713  edge_viapoint->setInformation(information);
714  edge_viapoint->setParameters(*cfg_, &(*vp_it));
715  optimizer_->addEdge(edge_viapoint);
716  }
717 }
718 
720 {
721  if (cfg_->robot.max_vel_y == 0) // non-holonomic robot
722  {
724  return; // if weight equals zero skip adding edges!
725 
726  int n = teb_.sizePoses();
727  Eigen::Matrix<double,2,2> information;
728  information(0,0) = cfg_->optim.weight_max_vel_x;
729  information(1,1) = cfg_->optim.weight_max_vel_theta;
730  information(0,1) = 0.0;
731  information(1,0) = 0.0;
732 
733  for (int i=0; i < n - 1; ++i)
734  {
735  EdgeVelocity* velocity_edge = new EdgeVelocity;
736  velocity_edge->setVertex(0,teb_.PoseVertex(i));
737  velocity_edge->setVertex(1,teb_.PoseVertex(i+1));
738  velocity_edge->setVertex(2,teb_.TimeDiffVertex(i));
739  velocity_edge->setInformation(information);
740  velocity_edge->setTebConfig(*cfg_);
741  optimizer_->addEdge(velocity_edge);
742  }
743  }
744  else // holonomic-robot
745  {
747  return; // if weight equals zero skip adding edges!
748 
749  int n = teb_.sizePoses();
750  Eigen::Matrix<double,3,3> information;
751  information.fill(0);
752  information(0,0) = cfg_->optim.weight_max_vel_x;
753  information(1,1) = cfg_->optim.weight_max_vel_y;
754  information(2,2) = cfg_->optim.weight_max_vel_theta;
755 
756  for (int i=0; i < n - 1; ++i)
757  {
758  EdgeVelocityHolonomic* velocity_edge = new EdgeVelocityHolonomic;
759  velocity_edge->setVertex(0,teb_.PoseVertex(i));
760  velocity_edge->setVertex(1,teb_.PoseVertex(i+1));
761  velocity_edge->setVertex(2,teb_.TimeDiffVertex(i));
762  velocity_edge->setInformation(information);
763  velocity_edge->setTebConfig(*cfg_);
764  optimizer_->addEdge(velocity_edge);
765  }
766 
767  }
768 }
769 
771 {
773  return; // if weight equals zero skip adding edges!
774 
775  int n = teb_.sizePoses();
776 
777  if (cfg_->robot.max_vel_y == 0 || cfg_->robot.acc_lim_y == 0) // non-holonomic robot
778  {
779  Eigen::Matrix<double,2,2> information;
780  information.fill(0);
781  information(0,0) = cfg_->optim.weight_acc_lim_x;
782  information(1,1) = cfg_->optim.weight_acc_lim_theta;
783 
784  // check if an initial velocity should be taken into accound
785  if (vel_start_.first)
786  {
787  EdgeAccelerationStart* acceleration_edge = new EdgeAccelerationStart;
788  acceleration_edge->setVertex(0,teb_.PoseVertex(0));
789  acceleration_edge->setVertex(1,teb_.PoseVertex(1));
790  acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0));
791  acceleration_edge->setInitialVelocity(vel_start_.second);
792  acceleration_edge->setInformation(information);
793  acceleration_edge->setTebConfig(*cfg_);
794  optimizer_->addEdge(acceleration_edge);
795  }
796 
797  // now add the usual acceleration edge for each tuple of three teb poses
798  for (int i=0; i < n - 2; ++i)
799  {
800  EdgeAcceleration* acceleration_edge = new EdgeAcceleration;
801  acceleration_edge->setVertex(0,teb_.PoseVertex(i));
802  acceleration_edge->setVertex(1,teb_.PoseVertex(i+1));
803  acceleration_edge->setVertex(2,teb_.PoseVertex(i+2));
804  acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i));
805  acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1));
806  acceleration_edge->setInformation(information);
807  acceleration_edge->setTebConfig(*cfg_);
808  optimizer_->addEdge(acceleration_edge);
809  }
810 
811  // check if a goal velocity should be taken into accound
812  if (vel_goal_.first)
813  {
814  EdgeAccelerationGoal* acceleration_edge = new EdgeAccelerationGoal;
815  acceleration_edge->setVertex(0,teb_.PoseVertex(n-2));
816  acceleration_edge->setVertex(1,teb_.PoseVertex(n-1));
817  acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 ));
818  acceleration_edge->setGoalVelocity(vel_goal_.second);
819  acceleration_edge->setInformation(information);
820  acceleration_edge->setTebConfig(*cfg_);
821  optimizer_->addEdge(acceleration_edge);
822  }
823  }
824  else // holonomic robot
825  {
826  Eigen::Matrix<double,3,3> information;
827  information.fill(0);
828  information(0,0) = cfg_->optim.weight_acc_lim_x;
829  information(1,1) = cfg_->optim.weight_acc_lim_y;
830  information(2,2) = cfg_->optim.weight_acc_lim_theta;
831 
832  // check if an initial velocity should be taken into accound
833  if (vel_start_.first)
834  {
836  acceleration_edge->setVertex(0,teb_.PoseVertex(0));
837  acceleration_edge->setVertex(1,teb_.PoseVertex(1));
838  acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0));
839  acceleration_edge->setInitialVelocity(vel_start_.second);
840  acceleration_edge->setInformation(information);
841  acceleration_edge->setTebConfig(*cfg_);
842  optimizer_->addEdge(acceleration_edge);
843  }
844 
845  // now add the usual acceleration edge for each tuple of three teb poses
846  for (int i=0; i < n - 2; ++i)
847  {
848  EdgeAccelerationHolonomic* acceleration_edge = new EdgeAccelerationHolonomic;
849  acceleration_edge->setVertex(0,teb_.PoseVertex(i));
850  acceleration_edge->setVertex(1,teb_.PoseVertex(i+1));
851  acceleration_edge->setVertex(2,teb_.PoseVertex(i+2));
852  acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i));
853  acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1));
854  acceleration_edge->setInformation(information);
855  acceleration_edge->setTebConfig(*cfg_);
856  optimizer_->addEdge(acceleration_edge);
857  }
858 
859  // check if a goal velocity should be taken into accound
860  if (vel_goal_.first)
861  {
863  acceleration_edge->setVertex(0,teb_.PoseVertex(n-2));
864  acceleration_edge->setVertex(1,teb_.PoseVertex(n-1));
865  acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 ));
866  acceleration_edge->setGoalVelocity(vel_goal_.second);
867  acceleration_edge->setInformation(information);
868  acceleration_edge->setTebConfig(*cfg_);
869  optimizer_->addEdge(acceleration_edge);
870  }
871  }
872 }
873 
874 
875 
877 {
878  if (cfg_->optim.weight_optimaltime==0)
879  return; // if weight equals zero skip adding edges!
880 
881  Eigen::Matrix<double,1,1> information;
882  information.fill(cfg_->optim.weight_optimaltime);
883 
884  for (int i=0; i < teb_.sizeTimeDiffs(); ++i)
885  {
886  EdgeTimeOptimal* timeoptimal_edge = new EdgeTimeOptimal;
887  timeoptimal_edge->setVertex(0,teb_.TimeDiffVertex(i));
888  timeoptimal_edge->setInformation(information);
889  timeoptimal_edge->setTebConfig(*cfg_);
890  optimizer_->addEdge(timeoptimal_edge);
891  }
892 }
893 
895 {
897  return; // if weight equals zero skip adding edges!
898 
899  Eigen::Matrix<double,1,1> information;
900  information.fill(cfg_->optim.weight_shortest_path);
901 
902  for (int i=0; i < teb_.sizePoses()-1; ++i)
903  {
904  EdgeShortestPath* shortest_path_edge = new EdgeShortestPath;
905  shortest_path_edge->setVertex(0,teb_.PoseVertex(i));
906  shortest_path_edge->setVertex(1,teb_.PoseVertex(i+1));
907  shortest_path_edge->setInformation(information);
908  shortest_path_edge->setTebConfig(*cfg_);
909  optimizer_->addEdge(shortest_path_edge);
910  }
911 }
912 
913 
914 
916 {
918  return; // if weight equals zero skip adding edges!
919 
920  // create edge for satisfiying kinematic constraints
921  Eigen::Matrix<double,2,2> information_kinematics;
922  information_kinematics.fill(0.0);
923  information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
924  information_kinematics(1, 1) = cfg_->optim.weight_kinematics_forward_drive;
925 
926  for (int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only
927  {
928  EdgeKinematicsDiffDrive* kinematics_edge = new EdgeKinematicsDiffDrive;
929  kinematics_edge->setVertex(0,teb_.PoseVertex(i));
930  kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));
931  kinematics_edge->setInformation(information_kinematics);
932  kinematics_edge->setTebConfig(*cfg_);
933  optimizer_->addEdge(kinematics_edge);
934  }
935 }
936 
938 {
940  return; // if weight equals zero skip adding edges!
941 
942  // create edge for satisfiying kinematic constraints
943  Eigen::Matrix<double,2,2> information_kinematics;
944  information_kinematics.fill(0.0);
945  information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
946  information_kinematics(1, 1) = cfg_->optim.weight_kinematics_turning_radius;
947 
948  for (int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only
949  {
950  EdgeKinematicsCarlike* kinematics_edge = new EdgeKinematicsCarlike;
951  kinematics_edge->setVertex(0,teb_.PoseVertex(i));
952  kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));
953  kinematics_edge->setInformation(information_kinematics);
954  kinematics_edge->setTebConfig(*cfg_);
955  optimizer_->addEdge(kinematics_edge);
956  }
957 }
958 
959 
961 {
962  //TODO(roesmann): Note, these edges can result in odd predictions, in particular
963  // we can observe a substantional mismatch between open- and closed-loop planning
964  // leading to a poor control performance.
965  // At the moment, we keep these functionality for oscillation recovery:
966  // Activating the edge for a short time period might not be crucial and
967  // could move the robot to a new oscillation-free state.
968  // This needs to be analyzed in more detail!
970  return; // if weight equals zero skip adding edges!
971 
973  {
974  ROS_WARN("TebOptimalPlanner::AddEdgesPreferRotDir(): unsupported RotType selected. Skipping edge creation.");
975  return;
976  }
977 
978  // create edge for satisfiying kinematic constraints
979  Eigen::Matrix<double,1,1> information_rotdir;
980  information_rotdir.fill(cfg_->optim.weight_prefer_rotdir);
981 
982  for (int i=0; i < teb_.sizePoses()-1 && i < 3; ++i) // currently: apply to first 3 rotations
983  {
984  EdgePreferRotDir* rotdir_edge = new EdgePreferRotDir;
985  rotdir_edge->setVertex(0,teb_.PoseVertex(i));
986  rotdir_edge->setVertex(1,teb_.PoseVertex(i+1));
987  rotdir_edge->setInformation(information_rotdir);
988 
990  rotdir_edge->preferLeft();
991  else if (prefer_rotdir_ == RotType::right)
992  rotdir_edge->preferRight();
993 
994  optimizer_->addEdge(rotdir_edge);
995  }
996 }
997 
998 void TebOptimalPlanner::computeCurrentCost(double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
999 {
1000  // check if graph is empty/exist -> important if function is called between buildGraph and optimizeGraph/clearGraph
1001  bool graph_exist_flag(false);
1002  if (optimizer_->edges().empty() && optimizer_->vertices().empty())
1003  {
1004  // here the graph is build again, for time efficiency make sure to call this function
1005  // between buildGraph and Optimize (deleted), but it depends on the application
1006  buildGraph();
1007  optimizer_->initializeOptimization();
1008  }
1009  else
1010  {
1011  graph_exist_flag = true;
1012  }
1013 
1014  optimizer_->computeInitialGuess();
1015 
1016  cost_ = 0;
1017 
1018  if (alternative_time_cost)
1019  {
1021  // TEST we use SumOfAllTimeDiffs() here, because edge cost depends on number of samples, which is not always the same for similar TEBs,
1022  // since we are using an AutoResize Function with hysteresis.
1023  }
1024 
1025  // now we need pointers to all edges -> calculate error for each edge-type
1026  // since we aren't storing edge pointers, we need to check every edge
1027  for (std::vector<g2o::OptimizableGraph::Edge*>::const_iterator it = optimizer_->activeEdges().begin(); it!= optimizer_->activeEdges().end(); it++)
1028  {
1029  double cur_cost = (*it)->chi2();
1030 
1031  if (dynamic_cast<EdgeObstacle*>(*it) != nullptr
1032  || dynamic_cast<EdgeInflatedObstacle*>(*it) != nullptr
1033  || dynamic_cast<EdgeDynamicObstacle*>(*it) != nullptr)
1034  {
1035  cur_cost *= obst_cost_scale;
1036  }
1037  else if (dynamic_cast<EdgeViaPoint*>(*it) != nullptr)
1038  {
1039  cur_cost *= viapoint_cost_scale;
1040  }
1041  else if (dynamic_cast<EdgeTimeOptimal*>(*it) != nullptr && alternative_time_cost)
1042  {
1043  continue; // skip these edges if alternative_time_cost is active
1044  }
1045  cost_ += cur_cost;
1046  }
1047 
1048  // delete temporary created graph
1049  if (!graph_exist_flag)
1050  clearGraph();
1051 }
1052 
1053 
1054 void TebOptimalPlanner::extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const
1055 {
1056  if (dt == 0)
1057  {
1058  vx = 0;
1059  vy = 0;
1060  omega = 0;
1061  return;
1062  }
1063 
1064  Eigen::Vector2d deltaS = pose2.position() - pose1.position();
1065 
1066  if (cfg_->robot.max_vel_y == 0) // nonholonomic robot
1067  {
1068  Eigen::Vector2d conf1dir( cos(pose1.theta()), sin(pose1.theta()) );
1069  // translational velocity
1070  double dir = deltaS.dot(conf1dir);
1071  vx = (double) g2o::sign(dir) * deltaS.norm()/dt;
1072  vy = 0;
1073  }
1074  else // holonomic robot
1075  {
1076  // transform pose 2 into the current robot frame (pose1)
1077  // for velocities only the rotation of the direction vector is necessary.
1078  // (map->pose1-frame: inverse 2d rotation matrix)
1079  double cos_theta1 = std::cos(pose1.theta());
1080  double sin_theta1 = std::sin(pose1.theta());
1081  double p1_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
1082  double p1_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
1083  vx = p1_dx / dt;
1084  vy = p1_dy / dt;
1085  }
1086 
1087  // rotational velocity
1088  double orientdiff = g2o::normalize_theta(pose2.theta() - pose1.theta());
1089  omega = orientdiff/dt;
1090 }
1091 
1092 bool TebOptimalPlanner::getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const
1093 {
1094  if (teb_.sizePoses()<2)
1095  {
1096  ROS_ERROR("TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist.");
1097  vx = 0;
1098  vy = 0;
1099  omega = 0;
1100  return false;
1101  }
1102  look_ahead_poses = std::max(1, std::min(look_ahead_poses, teb_.sizePoses() - 1));
1103  double dt = 0.0;
1104  for(int counter = 0; counter < look_ahead_poses; ++counter)
1105  {
1106  dt += teb_.TimeDiff(counter);
1107  if(dt >= cfg_->trajectory.dt_ref * look_ahead_poses) // TODO: change to look-ahead time? Refine trajectory?
1108  {
1109  look_ahead_poses = counter + 1;
1110  break;
1111  }
1112  }
1113  if (dt<=0)
1114  {
1115  ROS_ERROR("TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!");
1116  vx = 0;
1117  vy = 0;
1118  omega = 0;
1119  return false;
1120  }
1121 
1122  // Get velocity from the first two configurations
1123  extractVelocity(teb_.Pose(0), teb_.Pose(look_ahead_poses), dt, vx, vy, omega);
1124  return true;
1125 }
1126 
1127 void TebOptimalPlanner::getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const
1128 {
1129  int n = teb_.sizePoses();
1130  velocity_profile.resize( n+1 );
1131 
1132  // start velocity
1133  velocity_profile.front().linear.z = 0;
1134  velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0;
1135  velocity_profile.front().linear.x = vel_start_.second.linear.x;
1136  velocity_profile.front().linear.y = vel_start_.second.linear.y;
1137  velocity_profile.front().angular.z = vel_start_.second.angular.z;
1138 
1139  for (int i=1; i<n; ++i)
1140  {
1141  velocity_profile[i].linear.z = 0;
1142  velocity_profile[i].angular.x = velocity_profile[i].angular.y = 0;
1143  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);
1144  }
1145 
1146  // goal velocity
1147  velocity_profile.back().linear.z = 0;
1148  velocity_profile.back().angular.x = velocity_profile.back().angular.y = 0;
1149  velocity_profile.back().linear.x = vel_goal_.second.linear.x;
1150  velocity_profile.back().linear.y = vel_goal_.second.linear.y;
1151  velocity_profile.back().angular.z = vel_goal_.second.angular.z;
1152 }
1153 
1154 void TebOptimalPlanner::getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const
1155 {
1156  int n = teb_.sizePoses();
1157 
1158  trajectory.resize(n);
1159 
1160  if (n == 0)
1161  return;
1162 
1163  double curr_time = 0;
1164 
1165  // start
1166  TrajectoryPointMsg& start = trajectory.front();
1167  teb_.Pose(0).toPoseMsg(start.pose);
1168  start.velocity.linear.z = 0;
1169  start.velocity.angular.x = start.velocity.angular.y = 0;
1170  start.velocity.linear.x = vel_start_.second.linear.x;
1171  start.velocity.linear.y = vel_start_.second.linear.y;
1172  start.velocity.angular.z = vel_start_.second.angular.z;
1173  start.time_from_start.fromSec(curr_time);
1174 
1175  curr_time += teb_.TimeDiff(0);
1176 
1177  // intermediate points
1178  for (int i=1; i < n-1; ++i)
1179  {
1180  TrajectoryPointMsg& point = trajectory[i];
1181  teb_.Pose(i).toPoseMsg(point.pose);
1182  point.velocity.linear.z = 0;
1183  point.velocity.angular.x = point.velocity.angular.y = 0;
1184  double vel1_x, vel1_y, vel2_x, vel2_y, omega1, omega2;
1185  extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), vel1_x, vel1_y, omega1);
1186  extractVelocity(teb_.Pose(i), teb_.Pose(i+1), teb_.TimeDiff(i), vel2_x, vel2_y, omega2);
1187  point.velocity.linear.x = 0.5*(vel1_x+vel2_x);
1188  point.velocity.linear.y = 0.5*(vel1_y+vel2_y);
1189  point.velocity.angular.z = 0.5*(omega1+omega2);
1190  point.time_from_start.fromSec(curr_time);
1191 
1192  curr_time += teb_.TimeDiff(i);
1193  }
1194 
1195  // goal
1196  TrajectoryPointMsg& goal = trajectory.back();
1197  teb_.BackPose().toPoseMsg(goal.pose);
1198  goal.velocity.linear.z = 0;
1199  goal.velocity.angular.x = goal.velocity.angular.y = 0;
1200  goal.velocity.linear.x = vel_goal_.second.linear.x;
1201  goal.velocity.linear.y = vel_goal_.second.linear.y;
1202  goal.velocity.angular.z = vel_goal_.second.angular.z;
1203  goal.time_from_start.fromSec(curr_time);
1204 }
1205 
1206 
1207 bool TebOptimalPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
1208  double inscribed_radius, double circumscribed_radius, int look_ahead_idx)
1209 {
1210  if (look_ahead_idx < 0 || look_ahead_idx >= teb().sizePoses())
1211  look_ahead_idx = teb().sizePoses() - 1;
1212 
1213  for (int i=0; i <= look_ahead_idx; ++i)
1214  {
1215  if ( costmap_model->footprintCost(teb().Pose(i).x(), teb().Pose(i).y(), teb().Pose(i).theta(), footprint_spec, inscribed_radius, circumscribed_radius) < 0 )
1216  {
1217  if (visualization_)
1218  {
1219  visualization_->publishInfeasibleRobotPose(teb().Pose(i), *robot_model_);
1220  }
1221  return false;
1222  }
1223  // Checks if the distance between two poses is higher than the robot radius or the orientation diff is bigger than the specified threshold
1224  // and interpolates in that case.
1225  // (if obstacles are pushing two consecutive poses away, the center between two consecutive poses might coincide with the obstacle ;-)!
1226  if (i<look_ahead_idx)
1227  {
1228  double delta_rot = g2o::normalize_theta(g2o::normalize_theta(teb().Pose(i+1).theta()) -
1229  g2o::normalize_theta(teb().Pose(i).theta()));
1230  Eigen::Vector2d delta_dist = teb().Pose(i+1).position()-teb().Pose(i).position();
1231  if(fabs(delta_rot) > cfg_->trajectory.min_resolution_collision_check_angular || delta_dist.norm() > inscribed_radius)
1232  {
1233  int n_additional_samples = std::max(std::ceil(fabs(delta_rot) / cfg_->trajectory.min_resolution_collision_check_angular),
1234  std::ceil(delta_dist.norm() / inscribed_radius)) - 1;
1235  PoseSE2 intermediate_pose = teb().Pose(i);
1236  for(int step = 0; step < n_additional_samples; ++step)
1237  {
1238  intermediate_pose.position() = intermediate_pose.position() + delta_dist / (n_additional_samples + 1.0);
1239  intermediate_pose.theta() = g2o::normalize_theta(intermediate_pose.theta() +
1240  delta_rot / (n_additional_samples + 1.0));
1241  if ( costmap_model->footprintCost(intermediate_pose.x(), intermediate_pose.y(), intermediate_pose.theta(),
1242  footprint_spec, inscribed_radius, circumscribed_radius) == -1 )
1243  {
1244  if (visualization_)
1245  {
1246  visualization_->publishInfeasibleRobotPose(intermediate_pose, *robot_model_);
1247  }
1248  return false;
1249  }
1250  }
1251  }
1252  }
1253  }
1254  return true;
1255 }
1256 
1257 } // 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:96
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.
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.
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:164
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...
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:119
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:162
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. ...
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence) ...
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.
double weight_max_vel_theta
Optimization weight for satisfying the maximum allowed angular velocity.
Definition: teb_config.h:148
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:101
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
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:147
TFSIMD_FORCE_INLINE const tfScalar & y() const
void AddEdgesVelocity()
Add all edges (local cost functions) for limiting the translational and angular velocity.
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.
#define ROS_WARN(...)
double weight_kinematics_turning_radius
Optimization weight for enforcing a minimum turning radius (carlike robots)
Definition: teb_config.h:154
bool legacy_obstacle_association
If true, the old association strategy is used (for each obstacle, find the nearest TEB pose)...
Definition: teb_config.h:126
double weight_acc_lim_x
Optimization weight for satisfying the maximum allowed translational acceleration.
Definition: teb_config.h:149
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). ...
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.
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:215
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:150
virtual ~TebOptimalPlanner()
Destruct the optimal planner.
bool optimization_activate
Activate the optimization.
Definition: teb_config.h:141
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 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:127
double weight_max_vel_x
Optimization weight for satisfying the maximum allowed translational velocity.
Definition: teb_config.h:146
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 AddEdgesViaPoints()
Add all edges (local cost functions) related to minimizing the distance to via-points.
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
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:158
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
double weight_obstacle
Optimization weight for satisfying a minimum separation from obstacles.
Definition: teb_config.h:157
bool optimized_
This variable is true as long as the last optimization has been completed successful.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
TebOptimalPlanner()
Default constructor.
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
Edge defining the cost function for limiting the translational and rotational acceleration at the beg...
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
Definition: pose_se2.h:203
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
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:128
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:138
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
double weight_acc_lim_theta
Optimization weight for satisfying the maximum allowed angular acceleration.
Definition: teb_config.h:151
double weight_shortest_path
Optimization weight for contracting the trajectory w.r.t. path length.
Definition: teb_config.h:156
unsigned int step
double weight_dynamic_obstacle_inflation
Optimization weight for the inflation penalty of dynamic obstacles (should be small) ...
Definition: teb_config.h:160
int obstacle_poses_affected
The obstacle position is attached to the closest pose on the trajectory to reduce computational effor...
Definition: teb_config.h:125
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:159
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...
void setParameters(const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
Set all parameters at once.
double weight_optimaltime
Optimization weight for contracting the trajectory w.r.t. transition time.
Definition: teb_config.h:155
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:152
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 satisfying the non-holonomic kinematics of a carlike mobile robot...
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:122
void AddEdgesKinematicsCarlike()
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot...
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...
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
Definition: teb_config.h:161
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:139
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...
int sizePoses() const
Get the length of the internal pose sequence.
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:99
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.
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences) ...
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:120
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:153
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:94
bool optimization_verbose
Print verbose information.
Definition: teb_config.h:142
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...
#define ROS_DEBUG(...)


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