homotopy_class_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 #include <limits>
42 
43 namespace teb_local_planner
44 {
45 
46 HomotopyClassPlanner::HomotopyClassPlanner() : cfg_(NULL), obstacles_(NULL), via_points_(NULL), initial_plan_(NULL), initialized_(false)
47 {
48 }
49 
50 HomotopyClassPlanner::HomotopyClassPlanner(const TebConfig& cfg, ObstContainer* obstacles,
51  TebVisualizationPtr visual, const ViaPointContainer* via_points) : initial_plan_(NULL)
52 {
53  initialize(cfg, obstacles, visual, via_points);
54 }
55 
57 {
58 }
59 
60 void HomotopyClassPlanner::initialize(const TebConfig& cfg, ObstContainer* obstacles,
62 {
63  cfg_ = &cfg;
66 
68  graph_search_ = boost::shared_ptr<GraphSearchInterface>(new lrKeyPointGraph(*cfg_, this));
69  else
70  graph_search_ = boost::shared_ptr<GraphSearchInterface>(new ProbRoadmapGraph(*cfg_, this));
71 
72  std::random_device rd;
73  random_.seed(rd());
74 
75  initialized_ = true;
76 
78 }
79 
81 {
82  visualization_ = visualization;
83 }
84 
85 bool HomotopyClassPlanner::plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
86 {
87  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
88 
89  // store initial plan for further initializations (must be valid for the lifetime of this object or clearPlanner() is called!)
90  initial_plan_ = &initial_plan;
91 
92  PoseSE2 start(initial_plan.front().pose);
93  PoseSE2 goal(initial_plan.back().pose);
94 
95  return plan(start, goal, start_vel, free_goal_vel);
96 }
97 
98 
99 bool HomotopyClassPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
100 {
101  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
103  PoseSE2 goal_pose(goal);
104  return plan(start_pose, goal_pose, start_vel, free_goal_vel);
105 }
106 
107 bool HomotopyClassPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
108 {
109  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
110 
111  // Update old TEBs with new start, goal and velocity
112  updateAllTEBs(&start, &goal, start_vel);
113 
114  // Init new TEBs based on newly explored homotopy classes
115  exploreEquivalenceClassesAndInitTebs(start, goal, cfg_->obstacles.min_obstacle_dist, start_vel, free_goal_vel);
116  // update via-points if activated
118  // Optimize all trajectories in alternative homotopy classes
120  // Select which candidate (based on alternative homotopy classes) should be used
122 
123  initial_plan_ = nullptr; // clear pointer to any previous initial plan (any previous plan is useless regarding the h-signature);
124  return true;
125 }
126 
127 bool HomotopyClassPlanner::getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const
128 {
129  TebOptimalPlannerConstPtr best_teb = bestTeb();
130  if (!best_teb)
131  {
132  vx = 0;
133  vy = 0;
134  omega = 0;
135  return false;
136  }
137 
138  return best_teb->getVelocityCommand(vx, vy, omega, look_ahead_poses);
139 }
140 
141 
142 
143 
145 {
146  if (visualization_)
147  {
148  // Visualize graph
150  visualization_->publishGraph(graph_search_->graph_);
151 
152  // Visualize active tebs as marker
153  visualization_->publishTebContainer(tebs_);
154 
155  // Visualize best teb and feedback message if desired
156  TebOptimalPlannerConstPtr best_teb = bestTeb();
157  if (best_teb)
158  {
159  visualization_->publishLocalPlanAndPoses(best_teb->teb());
160 
161  if (best_teb->teb().sizePoses() > 0) //TODO maybe store current pose (start) within plan method as class field.
162  visualization_->publishRobotFootprintModel(best_teb->teb().Pose(0), *cfg_->robot_model);
163 
164  // feedback message
166  {
167  int best_idx = bestTebIdx();
168  if (best_idx>=0)
169  visualization_->publishFeedbackMessage(tebs_, (unsigned int) best_idx, *obstacles_);
170  }
171  }
172  }
173  else ROS_DEBUG("Ignoring HomotopyClassPlanner::visualize() call, since no visualization class was instantiated before.");
174 }
175 
176 
177 
179 {
180  // iterate existing h-signatures and check if there is an existing H-Signature similar the candidate
181  for (const std::pair<EquivalenceClassPtr, bool>& eqrel : equivalence_classes_)
182  {
183  if (eq_class->isEqual(*eqrel.first))
184  return true; // Found! Homotopy class already exists, therefore nothing added
185  }
186  return false;
187 }
188 
190 {
191  if (!eq_class)
192  return false;
193 
194  if (!eq_class->isValid())
195  {
196  ROS_WARN("HomotopyClassPlanner: Ignoring invalid H-signature");
197  return false;
198  }
199 
200  if (hasEquivalenceClass(eq_class))
201  {
202  // Allow up to configured number of Tebs that are in the same homotopy
203  // class as the current (best) Teb to avoid being stuck in a local minimum
205  return false;
206  }
207 
208  // Homotopy class not found -> Add to class-list, return that the h-signature is new
209  equivalence_classes_.push_back(std::make_pair(eq_class,lock));
210  return true;
211 }
212 
213 
215 {
216  // clear old h-signatures (since they could be changed due to new obstacle positions.
217  equivalence_classes_.clear();
218 
219  // Adding the equivalence class of the latest best_teb_ first
220  TebOptPlannerContainer::iterator it_best_teb = best_teb_ ? std::find(tebs_.begin(), tebs_.end(), best_teb_) : tebs_.end();
221  bool has_best_teb = it_best_teb != tebs_.end();
222  if (has_best_teb)
223  {
224  std::iter_swap(tebs_.begin(), it_best_teb); // Putting the last best teb at the beginning of the container
226  best_teb_->teb().poses().end(), getCplxFromVertexPosePtr , obstacles_,
227  best_teb_->teb().timediffs().begin(), best_teb_->teb().timediffs().end());
229  }
230  // Collect h-signatures for all existing TEBs and store them together with the corresponding iterator / pointer:
231 // typedef std::list< std::pair<TebOptPlannerContainer::iterator, std::complex<long double> > > TebCandidateType;
232 // TebCandidateType teb_candidates;
233 
234  // get new homotopy classes and delete multiple TEBs per homotopy class. Skips the best teb if available (added before).
235  TebOptPlannerContainer::iterator it_teb = has_best_teb ? std::next(tebs_.begin(), 1) : tebs_.begin();
236  while(it_teb != tebs_.end())
237  {
238  // calculate equivalence class for the current candidate
239  EquivalenceClassPtr equivalence_class = calculateEquivalenceClass(it_teb->get()->teb().poses().begin(), it_teb->get()->teb().poses().end(), getCplxFromVertexPosePtr , obstacles_,
240  it_teb->get()->teb().timediffs().begin(), it_teb->get()->teb().timediffs().end());
241 
242 // teb_candidates.push_back(std::make_pair(it_teb,H));
243 
244  // WORKAROUND until the commented code below works
245  // Here we do not compare cost values. Just first come first serve...
246  bool new_flag = addEquivalenceClassIfNew(equivalence_class);
247  if (!new_flag)
248  {
249  it_teb = tebs_.erase(it_teb);
250  continue;
251  }
252 
253  ++it_teb;
254  }
255  if(delete_detours)
257 
258  // Find multiple candidates and delete the one with higher cost
259  // TODO: this code needs to be adpated. Erasing tebs from the teb container_ could make iteratores stored in the candidate list invalid!
260 // TebCandidateType::reverse_iterator cand_i = teb_candidates.rbegin();
261 // int test_idx = 0;
262 // while (cand_i != teb_candidates.rend())
263 // {
264 //
265 // TebCandidateType::reverse_iterator cand_j = std::find_if(boost::next(cand_i),teb_candidates.rend(), boost::bind(compareH,_1,cand_i->second));
266 // if (cand_j != teb_candidates.rend() && cand_j != cand_i)
267 // {
268 // TebOptimalPlannerPtr pt1 = *(cand_j->first);
269 // TebOptimalPlannerPtr pt2 = *(cand_i->first);
270 // assert(pt1);
271 // assert(pt2);
272 // if ( cand_j->first->get()->getCurrentCost().sum() > cand_i->first->get()->getCurrentCost().sum() )
273 // {
274 // // found one that has higher cost, therefore erase cand_j
275 // tebs_.erase(cand_j->first);
276 // teb_candidates.erase(cand_j);
277 // }
278 // else // otherwise erase cand_i
279 // {
280 // tebs_.erase(cand_i->first);
281 // cand_i = teb_candidates.erase(cand_i);
282 // }
283 // }
284 // else
285 // {
286 // ROS_WARN_STREAM("increase cand_i");
287 // ++cand_i;
288 // }
289 // }
290 
291  // now add the h-signatures to the internal lookup-table (but only if there is no existing duplicate)
292 // for (TebCandidateType::iterator cand=teb_candidates.begin(); cand!=teb_candidates.end(); ++cand)
293 // {
294 // bool new_flag = addNewHSignatureIfNew(cand->second, cfg_->hcp.h_signature_threshold);
295 // if (!new_flag)
296 // {
297 // // ROS_ERROR_STREAM("getAndFilterHomotopyClassesTEB() - This schould not be happen.");
298 // tebs_.erase(cand->first);
299 // }
300 // }
301 
302 }
303 
305 {
306  if ( (!all_trajectories && !initial_plan_) || !via_points_ || via_points_->empty() || cfg_->optim.weight_viapoint <= 0)
307  return;
308 
309  if(equivalence_classes_.size() < tebs_.size())
310  {
311  ROS_ERROR("HomotopyClassPlanner::updateReferenceTrajectoryWithViaPoints(): Number of h-signatures does not match number of trajectories.");
312  return;
313  }
314 
315  if (all_trajectories)
316  {
317  // enable via-points for all tebs
318  for (std::size_t i=0; i < equivalence_classes_.size(); ++i)
319  {
320  tebs_[i]->setViaPoints(via_points_);
321  }
322  }
323  else
324  {
325  // enable via-points for teb in the same hommotopy class as the initial_plan and deactivate it for all other ones
326  for (std::size_t i=0; i < equivalence_classes_.size(); ++i)
327  {
328  if(initial_plan_eq_class_->isEqual(*equivalence_classes_[i].first))
329  tebs_[i]->setViaPoints(via_points_);
330  else
331  tebs_[i]->setViaPoints(NULL);
332  }
333  }
334 }
335 
336 
337 void HomotopyClassPlanner::exploreEquivalenceClassesAndInitTebs(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
338 {
339  // first process old trajectories
342 
343  // inject initial plan if available and not yet captured
344  if (initial_plan_)
345  {
346  initial_plan_teb_ = addAndInitNewTeb(*initial_plan_, start_vel, free_goal_vel);
347  }
348  else
349  {
350  initial_plan_teb_.reset();
351  initial_plan_teb_ = getInitialPlanTEB(); // this method searches for initial_plan_eq_class_ in the teb container (-> if !initial_plan_teb_)
352  }
353 
354  // now explore new homotopy classes and initialize tebs if new ones are found. The appropriate createGraph method is chosen via polymorphism.
355  graph_search_->createGraph(start,goal,dist_to_obst,cfg_->hcp.obstacle_heading_threshold, start_vel, free_goal_vel);
356 }
357 
358 
359 TebOptimalPlannerPtr HomotopyClassPlanner::addAndInitNewTeb(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_velocity, bool free_goal_vel)
360 {
361  if(tebs_.size() >= cfg_->hcp.max_number_classes)
362  return TebOptimalPlannerPtr();
363  TebOptimalPlannerPtr candidate = TebOptimalPlannerPtr( new TebOptimalPlanner(*cfg_, obstacles_, visualization_));
364 
365  candidate->teb().initTrajectoryToGoal(start, goal, 0, cfg_->robot.max_vel_x, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion);
366 
367  if (start_velocity)
368  candidate->setVelocityStart(*start_velocity);
369 
370  EquivalenceClassPtr H = calculateEquivalenceClass(candidate->teb().poses().begin(), candidate->teb().poses().end(), getCplxFromVertexPosePtr, obstacles_,
371  candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
372 
373  if (free_goal_vel)
374  candidate->setVelocityGoalFree();
375 
377  {
378  tebs_.push_back(candidate);
379  return tebs_.back();
380  }
381 
382  // If the candidate constitutes no new equivalence class, return a null pointer
383  return TebOptimalPlannerPtr();
384 }
385 
386 
388 {
389  bool answer = false;
390  if (best_teb_eq_class_)
391  answer = best_teb_eq_class_->isEqual(*eq_class);
392  return answer;
393 }
394 
396 {
397  int count = 0;
398  for (const std::pair<EquivalenceClassPtr, bool>& eqrel : equivalence_classes_)
399  {
400  if (eq_class->isEqual(*eqrel.first))
401  ++count;
402  }
403  return count;
404 }
405 
407 {
408  int count = 0;
409  if (best_teb_eq_class_)
411  return count;
412 }
413 
414 TebOptimalPlannerPtr HomotopyClassPlanner::addAndInitNewTeb(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_velocity, bool free_goal_vel)
415 {
416  if(tebs_.size() >= cfg_->hcp.max_number_classes)
417  return TebOptimalPlannerPtr();
418  TebOptimalPlannerPtr candidate = TebOptimalPlannerPtr( new TebOptimalPlanner(*cfg_, obstacles_, visualization_));
419 
420  candidate->teb().initTrajectoryToGoal(initial_plan, cfg_->robot.max_vel_x, cfg_->robot.max_vel_theta,
422 
423  if (start_velocity)
424  candidate->setVelocityStart(*start_velocity);
425 
426  if (free_goal_vel)
427  candidate->setVelocityGoalFree();
428 
429  // store the h signature of the initial plan to enable searching a matching teb later.
430  initial_plan_eq_class_ = calculateEquivalenceClass(candidate->teb().poses().begin(), candidate->teb().poses().end(), getCplxFromVertexPosePtr, obstacles_,
431  candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
432 
433  if(addEquivalenceClassIfNew(initial_plan_eq_class_, true)) // also prevent candidate from deletion
434  {
435  tebs_.push_back(candidate);
436  return tebs_.back();
437  }
438 
439  // If the candidate constitutes no new equivalence class, return a null pointer
440  return TebOptimalPlannerPtr();
441 }
442 
443 void HomotopyClassPlanner::updateAllTEBs(const PoseSE2* start, const PoseSE2* goal, const geometry_msgs::Twist* start_velocity)
444 {
445  // If new goal is too far away, clear all existing trajectories to let them reinitialize later.
446  // Since all Tebs are sharing the same fixed goal pose, just take the first candidate:
447  if (!tebs_.empty()
448  && ((goal->position() - tebs_.front()->teb().BackPose().position()).norm() >= cfg_->trajectory.force_reinit_new_goal_dist
449  || fabs(g2o::normalize_theta(goal->theta() - tebs_.front()->teb().BackPose().theta())) >= cfg_->trajectory.force_reinit_new_goal_angular))
450  {
451  ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
452  tebs_.clear();
453  equivalence_classes_.clear();
454  }
455 
456  // hot-start from previous solutions
457  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
458  {
459  it_teb->get()->teb().updateAndPruneTEB(*start, *goal);
460  if (start_velocity)
461  it_teb->get()->setVelocityStart(*start_velocity);
462  }
463 }
464 
465 
466 void HomotopyClassPlanner::optimizeAllTEBs(int iter_innerloop, int iter_outerloop)
467 {
468  // optimize TEBs in parallel since they are independend of each other
470  {
471  // Must prevent .join_all() from throwing exception if interruption was
472  // requested, as this can lead to multiple threads operating on the same
473  // TEB, which leads to SIGSEGV
474  boost::this_thread::disable_interruption di;
475 
476  boost::thread_group teb_threads;
477  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
478  {
479  teb_threads.create_thread( boost::bind(&TebOptimalPlanner::optimizeTEB, it_teb->get(), iter_innerloop, iter_outerloop,
482  }
483  teb_threads.join_all();
484  }
485  else
486  {
487  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
488  {
489  it_teb->get()->optimizeTEB(iter_innerloop,iter_outerloop, true, cfg_->hcp.selection_obst_cost_scale,
490  cfg_->hcp.selection_viapoint_cost_scale, cfg_->hcp.selection_alternative_time_cost); // compute cost as well inside optimizeTEB (last argument = true)
491  }
492  }
493 }
494 
496 {
497  // first check stored teb object
498  if (initial_plan_teb_)
499  {
500  // check if the teb is still part of the teb container
501  if ( std::find(tebs_.begin(), tebs_.end(), initial_plan_teb_ ) != tebs_.end() )
503  else
504  {
505  initial_plan_teb_.reset(); // reset pointer for next call
506  ROS_DEBUG("initial teb not found, trying to find a match according to the cached equivalence class");
507  }
508  }
509 
510  // reset the locked state for equivalence classes // TODO: this might be adapted if not only the plan containing the initial plan is locked!
511  for (int i=0; i<equivalence_classes_.size(); ++i)
512  {
513  equivalence_classes_[i].second = false;
514  }
515 
516  // otherwise check if the stored reference equivalence class exist in the list of known classes
518  {
519  if (equivalence_classes_.size() == tebs_.size())
520  {
521  for (int i=0; i<equivalence_classes_.size(); ++i)
522  {
523  if (equivalence_classes_[i].first->isEqual(*initial_plan_eq_class_))
524  {
525  equivalence_classes_[i].second = true;
526  return tebs_[i];
527  }
528  }
529  }
530  else
531  ROS_ERROR("HomotopyClassPlanner::getInitialPlanTEB(): number of equivalence classes (%lu) and number of trajectories (%lu) does not match.", equivalence_classes_.size(), tebs_.size());
532  }
533  else
534  ROS_DEBUG("HomotopyClassPlanner::getInitialPlanTEB(): initial TEB not found in the set of available trajectories.");
535 
536  return TebOptimalPlannerPtr();
537 }
538 
540 {
542  {
543  return;
544  }
545  // interate both vectors in parallel
546  auto it_eqrel = equivalence_classes_.begin();
547  auto it_teb = tebs_.begin();
548  while (it_teb != tebs_.end() && it_eqrel != equivalence_classes_.end())
549  {
550  if (it_teb->get() != best_teb_.get() // Always preserve the "best" teb
552  {
553  it_teb = tebs_.erase(it_teb);
554  it_eqrel = equivalence_classes_.erase(it_eqrel);
555  }
556  else
557  {
558  ++it_teb;
559  ++it_eqrel;
560  }
561  }
562 }
563 
565 {
566  double min_cost = std::numeric_limits<double>::max(); // maximum cost
567  double min_cost_last_best = std::numeric_limits<double>::max();
568  double min_cost_initial_plan_teb = std::numeric_limits<double>::max();
569  TebOptimalPlannerPtr initial_plan_teb = getInitialPlanTEB();
570 
571  // check if last best_teb is still a valid candidate
572  if (best_teb_ && std::find(tebs_.begin(), tebs_.end(), best_teb_) != tebs_.end())
573  {
574  // get cost of this candidate
575  min_cost_last_best = best_teb_->getCurrentCost() * cfg_->hcp.selection_cost_hysteresis; // small hysteresis
577  }
578  else
579  {
580  last_best_teb_.reset();
581  }
582 
583  if (initial_plan_teb) // the validity was already checked in getInitialPlanTEB()
584  {
585  // get cost of this candidate
586  min_cost_initial_plan_teb = initial_plan_teb->getCurrentCost() * cfg_->hcp.selection_prefer_initial_plan; // small hysteresis
587  }
588 
589 
590  best_teb_.reset(); // reset pointer
591 
592  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
593  {
594  // check if the related TEB leaves the local costmap region
595 // if (tebs_.size()>1 && !(*it_teb)->teb().isTrajectoryInsideRegion(20, -1, 1))
596 // {
597 // ROS_INFO("HomotopyClassPlanner::selectBestTeb(): skipping trajectories that are not inside the local costmap");
598 // continue;
599 // }
600 
601  double teb_cost;
602 
603  if (*it_teb == last_best_teb_)
604  teb_cost = min_cost_last_best; // skip already known cost value of the last best_teb
605  else if (*it_teb == initial_plan_teb)
606  teb_cost = min_cost_initial_plan_teb;
607  else
608  teb_cost = it_teb->get()->getCurrentCost();
609 
610  if (teb_cost < min_cost)
611  {
612  // check if this candidate is currently not selected
613  best_teb_ = *it_teb;
614  min_cost = teb_cost;
615  }
616  }
617 
618 
619  // in case we haven't found any teb due to some previous checks, investigate list again
620 // if (!best_teb_ && !tebs_.empty())
621 // {
622 // ROS_DEBUG("all " << tebs_.size() << " tebs rejected previously");
623 // if (tebs_.size()==1)
624 // best_teb_ = tebs_.front();
625 // else // if multiple TEBs are available:
626 // {
627 // // try to use the one that relates to the initial plan
628 // TebOptimalPlannerPtr initial_plan_teb = getInitialPlanTEB();
629 // if (initial_plan_teb)
630 // best_teb_ = initial_plan_teb;
631 // else
632 // {
633 // // now compute the cost for the rest (we haven't computed it before)
634 // for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
635 // {
636 // double teb_cost = it_teb->get()->getCurrentCost();
637 // if (teb_cost < min_cost)
638 // {
639 // // check if this candidate is currently not selected
640 // best_teb_ = *it_teb;
641 // min_cost = teb_cost;
642 // }
643 // }
644 // }
645 // }
646 // }
647 
648  // check if we are allowed to change
650  {
651  ros::Time now = ros::Time::now();
653  {
655  }
656  else
657  {
658  ROS_DEBUG("HomotopyClassPlanner::selectBestTeb(): Switching equivalence classes blocked (check parameter switching_blocking_period.");
659  // block switching, so revert best_teb_
661  }
662 
663  }
664 
665 
666  return best_teb_;
667 }
668 
670 {
671  if (tebs_.size() == 1)
672  return 0;
673 
674  if (!best_teb_)
675  return -1;
676 
677  int idx = 0;
678  for (TebOptPlannerContainer::const_iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb, ++idx)
679  {
680  if (*it_teb == best_teb_)
681  return idx;
682  }
683  return -1;
684 }
685 
686 bool HomotopyClassPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
687  double inscribed_radius, double circumscribed_radius, int look_ahead_idx, double feasibility_check_lookahead_distance)
688 {
689  bool feasible = false;
690  while(ros::ok() && !feasible && tebs_.size() > 0)
691  {
693  if (!best)
694  {
695  ROS_ERROR("Couldn't retrieve the best plan");
696  return false;
697  }
698  feasible = best->isTrajectoryFeasible(costmap_model, footprint_spec, inscribed_radius, circumscribed_radius, look_ahead_idx, feasibility_check_lookahead_distance);
699  if(!feasible)
700  {
701  removeTeb(best);
702  if(last_best_teb_ && (last_best_teb_ == best)) // Same plan as before.
703  return feasible; // Not failing could result in oscillations between trajectories.
704  }
705  }
706  return feasible;
707 }
708 
710 {
711  if(tebs_.empty())
712  return TebOptimalPlannerPtr();
713  if (!best_teb_ || std::find(tebs_.begin(), tebs_.end(), best_teb_) == tebs_.end())
715  return best_teb_;
716 }
717 
718 TebOptPlannerContainer::iterator HomotopyClassPlanner::removeTeb(TebOptimalPlannerPtr& teb)
719 {
720  TebOptPlannerContainer::iterator return_iterator = tebs_.end();
721  if(equivalence_classes_.size() != tebs_.size())
722  {
723  ROS_ERROR("removeTeb: size of eq classes != size of tebs");
724  return return_iterator;
725  }
726  auto it_eq_classes = equivalence_classes_.begin();
727  for(auto it = tebs_.begin(); it != tebs_.end(); ++it)
728  {
729  if(*it == teb)
730  {
731  return_iterator = tebs_.erase(it);
732  equivalence_classes_.erase(it_eq_classes);
733  break;
734  }
735  ++it_eq_classes;
736  }
737  return return_iterator;
738 }
739 
741 {
742  // set preferred turning dir for all TEBs
743  for (TebOptPlannerContainer::const_iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
744  {
745  (*it_teb)->setPreferredTurningDir(dir);
746  }
747 }
748 
750 {
751  // Early return if there is no best trajectory initialized
752  if (!best_teb_)
753  return false;
754 
755  return best_teb_->hasDiverged();
756 }
757 
758 void HomotopyClassPlanner::computeCurrentCost(std::vector<double>& cost, double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
759 {
760  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
761  {
762  it_teb->get()->computeCurrentCost(cost, obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
763  }
764 }
765 
766 void HomotopyClassPlanner::deletePlansDetouringBackwards(const double orient_threshold,
767  const double len_orientation_vector)
768 {
769  if (tebs_.size() < 2 || !best_teb_ || std::find(tebs_.begin(), tebs_.end(), best_teb_) == tebs_.end() ||
770  best_teb_->teb().sizePoses() < 2)
771  {
772  return; // A moving direction wasn't chosen yet
773  }
774  double current_movement_orientation;
775  double best_plan_duration = std::max(best_teb_->teb().getSumOfAllTimeDiffs(), 1.0);
776  if(!computeStartOrientation(best_teb_, len_orientation_vector, current_movement_orientation))
777  return; // The plan is shorter than len_orientation_vector
778  for(auto it_teb = tebs_.begin(); it_teb != tebs_.end();)
779  {
780  if(*it_teb == best_teb_) // The current plan should not be considered a detour
781  {
782  ++it_teb;
783  continue;
784  }
785  if((*it_teb)->teb().sizePoses() < 2)
786  {
787  ROS_DEBUG("Discarding a plan with less than 2 poses");
788  it_teb = removeTeb(*it_teb);
789  continue;
790  }
791  double plan_orientation;
792  if(!computeStartOrientation(*it_teb, len_orientation_vector, plan_orientation))
793  {
794  ROS_DEBUG("Failed to compute the start orientation for one of the tebs, likely close to the target");
795  it_teb = removeTeb(*it_teb);
796  continue;
797  }
798  if(fabs(g2o::normalize_theta(plan_orientation - current_movement_orientation)) > orient_threshold)
799  {
800  it_teb = removeTeb(*it_teb); // Plan detouring backwards
801  continue;
802  }
803  if(!it_teb->get()->isOptimized())
804  {
805  ROS_DEBUG("Removing a teb because it's not optimized");
806  it_teb = removeTeb(*it_teb); // Deletes tebs that cannot be optimized (last optim call failed)
807  continue;
808  }
809  if(it_teb->get()->teb().getSumOfAllTimeDiffs() / best_plan_duration > cfg_->hcp.max_ratio_detours_duration_best_duration)
810  {
811  ROS_DEBUG("Removing a teb because it's duration is much longer than that of the best teb");
812  it_teb = removeTeb(*it_teb);
813  continue;
814  }
815  ++it_teb;
816  }
817 }
818 
819 bool HomotopyClassPlanner::computeStartOrientation(const TebOptimalPlannerPtr plan, const double len_orientation_vector,
820  double& orientation)
821 {
822  VertexPose start_pose = plan->teb().Pose(0);
823  bool second_pose_found = false;
824  Eigen::Vector2d start_vector;
825  for(auto& pose : plan->teb().poses())
826  {
827  start_vector = start_pose.position() - pose->position();
828  if(start_vector.norm() > len_orientation_vector)
829  {
830  second_pose_found = true;
831  break;
832  }
833  }
834  if(!second_pose_found) // The current plan is too short to make assumptions on the start orientation
835  return false;
836  orientation = std::atan2(start_vector[1], start_vector[0]);
837  return true;
838 }
839 
840 
841 } // end namespace
teb_local_planner::HomotopyClassPlanner::obstacles
const ObstContainer * obstacles() const
Access current obstacle container (read-only)
Definition: homotopy_class_planner.h:489
teb_local_planner::TebConfig::HomotopyClasses::switching_blocking_period
double switching_blocking_period
Specify a time duration in seconds that needs to be expired before a switch to new equivalence class ...
Definition: teb_config.h:196
teb_local_planner::HomotopyClassPlanner::addEquivalenceClassIfNew
bool addEquivalenceClassIfNew(const EquivalenceClassPtr &eq_class, bool lock=false)
Internal helper function that adds a new equivalence class to the list of known classes only if it is...
Definition: homotopy_class_planner.cpp:225
teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_angular
double force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
Definition: teb_config.h:87
teb_local_planner::TebConfig::Optimization::weight_viapoint
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
Definition: teb_config.h:175
cmd_vel_to_ackermann_drive.Twist
Twist
Definition: cmd_vel_to_ackermann_drive.py:56
teb_local_planner::HomotopyClassPlanner::getVelocityCommand
virtual bool getVelocityCommand(double &vx, double &vy, double &omega, int look_ahead_poses) const
Get the velocity command from a previously optimized plan to control the robot at the current samplin...
Definition: homotopy_class_planner.cpp:163
teb_local_planner::HomotopyClassPlanner::isInBestTebClass
bool isInBestTebClass(const EquivalenceClassPtr &eq_class) const
Definition: homotopy_class_planner.cpp:423
teb_local_planner::TebOptimalPlanner::optimizeTEB
bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards=false, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Optimize a previously initialized trajectory (actual TEB optimization loop).
Definition: optimal_planner.cpp:218
teb_local_planner::HomotopyClassPlanner::bestTeb
TebOptimalPlannerPtr bestTeb() const
Access current best trajectory candidate (that relates to the "best" homotopy class).
Definition: homotopy_class_planner.h:243
boost::shared_ptr
via_points
ViaPointContainer via_points
Definition: test_optim_node.cpp:55
teb_local_planner::HomotopyClassPlanner::visualize
virtual void visualize()
Publish the local plan, pose sequence and additional information via ros topics (e....
Definition: homotopy_class_planner.cpp:180
teb_local_planner::HomotopyClassPlanner::isTrajectoryFeasible
virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0)
Check whether the planned trajectory is feasible or not.
Definition: homotopy_class_planner.cpp:722
teb_local_planner::HomotopyClassPlanner::computeCurrentCost
virtual void computeCurrentCost(std::vector< double > &cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Definition: homotopy_class_planner.cpp:794
teb_local_planner::TebConfig::HomotopyClasses::max_ratio_detours_duration_best_duration
double max_ratio_detours_duration_best_duration
Detours are discarted if their execution time / the execution time of the best teb is > this.
Definition: teb_config.h:214
teb_local_planner::HomotopyClassPlanner::via_points_
const ViaPointContainer * via_points_
Store the current list of via-points.
Definition: homotopy_class_planner.h:582
teb_local_planner::TebConfig::HomotopyClasses::selection_dropping_probability
double selection_dropping_probability
At each planning cycle, TEBs other than the current 'best' one will be randomly dropped with this pro...
Definition: teb_config.h:195
teb_local_planner::HomotopyClassPlanner::initial_plan_
const std::vector< geometry_msgs::PoseStamped > * initial_plan_
Store the initial plan if available for a better trajectory initialization.
Definition: homotopy_class_planner.h:589
teb_local_planner::TebConfig::Trajectory::publish_feedback
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
Definition: teb_config.h:90
teb_local_planner::HomotopyClassPlanner::last_eq_class_switching_time_
ros::Time last_eq_class_switching_time_
Store the time at which the equivalence class changed recently.
Definition: homotopy_class_planner.h:600
teb_local_planner::HomotopyClassPlanner::obstacles_
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
Definition: homotopy_class_planner.h:581
export_to_svg.goal_pose
list goal_pose
Definition: export_to_svg.py:198
teb_local_planner::HomotopyClassPlanner::hasDiverged
bool hasDiverged() const override
Returns true if the planner has diverged.
Definition: homotopy_class_planner.cpp:785
teb_local_planner::TebConfig::HomotopyClasses::simple_exploration
bool simple_exploration
If true, distinctive trajectories are explored using a simple left-right approach (pass each obstacle...
Definition: teb_config.h:187
teb_local_planner::TebConfig::hcp
struct teb_local_planner::TebConfig::HomotopyClasses hcp
teb_local_planner::HomotopyClassPlanner::numTebsInBestTebClass
int numTebsInBestTebClass() const
Definition: homotopy_class_planner.cpp:442
teb_local_planner::TebConfig::HomotopyClasses::delete_detours_backwards
bool delete_detours_backwards
If enabled, the planner will discard the plans detouring backwards with respect to the best plan.
Definition: teb_config.h:211
teb_local_planner::HomotopyClassPlanner::addAndInitNewTeb
TebOptimalPlannerPtr addAndInitNewTeb(BidirIter path_start, BidirIter path_end, Fun fun_position, double start_orientation, double goal_orientation, const geometry_msgs::Twist *start_velocity, bool free_goal_vel=false)
Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class....
Definition: homotopy_class_planner.hpp:102
teb_local_planner::HomotopyClassPlanner::initial_plan_eq_class_
EquivalenceClassPtr initial_plan_eq_class_
Store the equivalence class of the initial plan.
Definition: homotopy_class_planner.h:590
teb_local_planner::HomotopyClassPlanner::initialize
void initialize(const TebConfig &cfg, ObstContainer *obstacles=NULL, TebVisualizationPtr visualization=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL)
Initialize the HomotopyClassPlanner.
Definition: homotopy_class_planner.cpp:96
teb_local_planner::TebConfig::HomotopyClasses::enable_multithreading
bool enable_multithreading
Activate multiple threading for planning multiple trajectories in parallel.
Definition: teb_config.h:186
teb_local_planner::TebConfig::HomotopyClasses::max_number_plans_in_current_class
int max_number_plans_in_current_class
Specify the maximum number of trajectories to try that are in the same homotopy class as the current ...
Definition: teb_config.h:189
ros::ok
ROSCPP_DECL bool ok()
teb_local_planner::RotType
RotType
Symbols for left/none/right rotations
Definition: misc.h:89
teb_local_planner::TebConfig::HomotopyClasses::max_number_classes
int max_number_classes
Specify the maximum number of allowed alternative homotopy classes (limits computational effort)
Definition: teb_config.h:188
teb_local_planner::TebConfig::Optimization::no_outer_iterations
int no_outer_iterations
Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with...
Definition: teb_config.h:152
teb_local_planner::HomotopyClassPlanner::getInitialPlanTEB
TebOptimalPlannerPtr getInitialPlanTEB()
Returns a shared pointer to the TEB related to the initial plan.
Definition: homotopy_class_planner.cpp:531
teb_local_planner::HomotopyClassPlanner::visualization_
TebVisualizationPtr visualization_
Instance of the visualization class (local/global plan, obstacles, ...)
Definition: homotopy_class_planner.h:585
teb_local_planner::TebConfig::Optimization::no_inner_iterations
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
Definition: teb_config.h:151
teb_local_planner::TebOptimalPlannerPtr
boost::shared_ptr< TebOptimalPlanner > TebOptimalPlannerPtr
Abbrev. for shared instances of the TebOptimalPlanner.
Definition: optimal_planner.h:734
base_local_planner::CostmapModel
teb_local_planner::HomotopyClassPlanner::computeStartOrientation
bool computeStartOrientation(const TebOptimalPlannerPtr plan, const double len_orientation_vector, double &orientation)
Given a plan, computes its start orientation using a vector of length >= len_orientation_vector start...
Definition: homotopy_class_planner.cpp:855
teb_local_planner::TebConfig::HomotopyClasses::selection_prefer_initial_plan
double selection_prefer_initial_plan
Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the ini...
Definition: teb_config.h:191
teb_local_planner::HomotopyClassPlanner::calculateEquivalenceClass
EquivalenceClassPtr calculateEquivalenceClass(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer *obstacles=NULL, boost::optional< TimeDiffSequence::iterator > timediff_start=boost::none, boost::optional< TimeDiffSequence::iterator > timediff_end=boost::none)
Calculate the equivalence class of a path.
Definition: homotopy_class_planner.hpp:83
teb_local_planner::TebConfig::HomotopyClasses::viapoints_all_candidates
bool viapoints_all_candidates
If true, all trajectories of different topologies are attached to the current set of via-points,...
Definition: teb_config.h:207
teb_local_planner::HomotopyClassPlanner::plan
virtual bool plan(const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false)
Plan a trajectory based on an initial reference plan.
Definition: homotopy_class_planner.cpp:121
ROS_DEBUG
#define ROS_DEBUG(...)
visual
TebVisualizationPtr visual
Definition: test_optim_node.cpp:53
teb_local_planner::HomotopyClassPlanner::last_best_teb_
TebOptimalPlannerPtr last_best_teb_
Points to the plan used in the previous control cycle.
Definition: homotopy_class_planner.h:605
teb_local_planner::TebConfig::HomotopyClasses::length_start_orientation_vector
double length_start_orientation_vector
Length of the vector used to compute the start orientation of a plan.
Definition: teb_config.h:213
export_to_svg.start_pose
list start_pose
Definition: export_to_svg.py:197
teb_local_planner::TebConfig::trajectory
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
teb_local_planner::TebConfig::Obstacles::min_obstacle_dist
double min_obstacle_dist
Minimum desired separation from obstacles.
Definition: teb_config.h:129
teb_local_planner::HomotopyClassPlanner::random_
std::default_random_engine random_
Definition: homotopy_class_planner.h:602
teb_local_planner::TebConfig::HomotopyClasses::detours_orientation_tolerance
double detours_orientation_tolerance
A plan is considered a detour if its start orientation differs more than this from the best plan.
Definition: teb_config.h:212
teb_local_planner::TebConfig::Trajectory::global_plan_overwrite_orientation
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
Definition: teb_config.h:79
teb_local_planner::PoseSE2::theta
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: pose_se2.h:218
teb_local_planner::ObstContainer
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:333
teb_local_planner::getCplxFromVertexPosePtr
std::complex< long double > getCplxFromVertexPosePtr(const VertexPose *pose)
< Inline function used for calculateHSignature() in combination with VertexPose pointers
Definition: homotopy_class_planner.h:108
teb_local_planner::PoseSE2::position
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:181
teb_local_planner::TebConfig::robot
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
teb_local_planner::HomotopyClassPlanner::selectBestTeb
TebOptimalPlannerPtr selectBestTeb()
In case of multiple, internally stored, alternative trajectories, select the best one according to th...
Definition: homotopy_class_planner.cpp:600
teb_local_planner::TebConfig::HomotopyClasses::selection_obst_cost_scale
double selection_obst_cost_scale
Extra scaling of obstacle cost terms just for selecting the 'best' candidate.
Definition: teb_config.h:192
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
homotopy_class_planner.h
ROS_WARN
#define ROS_WARN(...)
teb_local_planner::HomotopyClassPlanner::hasEquivalenceClass
bool hasEquivalenceClass(const EquivalenceClassPtr &eq_class) const
Check if a h-signature exists already.
Definition: homotopy_class_planner.cpp:214
teb_local_planner::TebVisualizationPtr
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
Definition: visualization.h:311
teb_local_planner::HomotopyClassPlanner::deletePlansDetouringBackwards
void deletePlansDetouringBackwards(const double orient_threshold, const double len_orientation_vector)
Checks if the orientation of the computed trajectories differs from that of the best plan of more tha...
Definition: homotopy_class_planner.cpp:802
teb_local_planner::EquivalenceClassPtr
boost::shared_ptr< EquivalenceClass > EquivalenceClassPtr
Definition: equivalence_relations.h:133
tf::Transform
teb_local_planner::TebConfig::HomotopyClasses::selection_cost_hysteresis
double selection_cost_hysteresis
Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in...
Definition: teb_config.h:190
teb_local_planner::HomotopyClassPlanner::updateAllTEBs
void updateAllTEBs(const PoseSE2 *start, const PoseSE2 *goal, const geometry_msgs::Twist *start_velocity)
Update TEBs with new pose, goal and current velocity.
Definition: homotopy_class_planner.cpp:479
teb_local_planner::TebConfig::Trajectory::force_reinit_new_goal_dist
double force_reinit_new_goal_dist
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specifie...
Definition: teb_config.h:86
teb_local_planner::TebConfig::Trajectory::allow_init_with_backwards_motion
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
Definition: teb_config.h:80
teb_local_planner::TebConfig::HomotopyClasses::selection_viapoint_cost_scale
double selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the 'best' candidate.
Definition: teb_config.h:193
teb_local_planner::HomotopyClassPlanner::initialized_
bool initialized_
Keeps track about the correct initialization of this class.
Definition: homotopy_class_planner.h:603
teb_local_planner::HomotopyClassPlanner::best_teb_eq_class_
EquivalenceClassPtr best_teb_eq_class_
Store the equivalence class of the current best teb.
Definition: homotopy_class_planner.h:587
start
ROSCPP_DECL void start()
teb_local_planner::TebConfig::HomotopyClasses::obstacle_heading_threshold
double obstacle_heading_threshold
Specify the value of the normalized scalar product between obstacle heading and goal heading in order...
Definition: teb_config.h:205
teb_local_planner::HomotopyClassPlanner::HomotopyClassPlanner
HomotopyClassPlanner()
Default constructor.
Definition: homotopy_class_planner.cpp:82
teb_local_planner::TebConfig::Robot::max_vel_x
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:99
teb_local_planner::HomotopyClassPlanner::~HomotopyClassPlanner
virtual ~HomotopyClassPlanner()
Destruct the HomotopyClassPlanner.
Definition: homotopy_class_planner.cpp:92
teb_local_planner::TebConfig::obstacles
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
teb_local_planner::PoseSE2
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:93
teb_local_planner::HomotopyClassPlanner::setVisualization
void setVisualization(TebVisualizationPtr visualization)
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and ...
Definition: homotopy_class_planner.cpp:116
ros::Time
teb_local_planner::HomotopyClassPlanner::tebs_
TebOptPlannerContainer tebs_
Container that stores multiple local teb planners (for alternative equivalence classes) and their cor...
Definition: homotopy_class_planner.h:593
teb_local_planner::TebConfig::Trajectory::min_samples
int min_samples
Minimum number of samples (should be always greater than 2)
Definition: teb_config.h:77
teb_local_planner::HomotopyClassPlanner::removeTeb
TebOptPlannerContainer::iterator removeTeb(TebOptimalPlannerPtr &teb)
Removes the specified teb and the corresponding homotopy class from the list of available ones.
Definition: homotopy_class_planner.cpp:754
teb_local_planner::HomotopyClassPlanner::graph_search_
boost::shared_ptr< GraphSearchInterface > graph_search_
Definition: homotopy_class_planner.h:598
teb_local_planner::HomotopyClassPlanner::randomlyDropTebs
void randomlyDropTebs()
Randomly drop non-optimal TEBs to so we can explore other alternatives.
Definition: homotopy_class_planner.cpp:575
teb_local_planner::HomotopyClassPlanner::best_teb_
TebOptimalPlannerPtr best_teb_
Store the current best teb.
Definition: homotopy_class_planner.h:586
teb_local_planner::HomotopyClassPlanner::setPreferredTurningDir
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
Definition: homotopy_class_planner.cpp:776
initialize
ROSCONSOLE_DECL void initialize()
ROS_ERROR
#define ROS_ERROR(...)
teb_local_planner::HomotopyClassPlanner::renewAndAnalyzeOldTebs
void renewAndAnalyzeOldTebs(bool delete_detours)
Renew all found h-signatures for the new planning step based on existing TEBs. Optionally detours can...
Definition: homotopy_class_planner.cpp:250
teb_local_planner::TebConfig::HomotopyClasses::visualize_hc_graph
bool visualize_hc_graph
Visualize the graph that is created for exploring new homotopy classes.
Definition: teb_config.h:209
teb_local_planner::HomotopyClassPlanner::optimizeAllTEBs
void optimizeAllTEBs(int iter_innerloop, int iter_outerloop)
Optimize all available trajectories by invoking the optimizer on each one.
Definition: homotopy_class_planner.cpp:502
teb_local_planner::TebConfig::robot_model
RobotFootprintModelPtr robot_model
model of the robot's footprint
Definition: teb_config.h:69
teb_local_planner::HomotopyClassPlanner::exploreEquivalenceClassesAndInitTebs
void exploreEquivalenceClassesAndInitTebs(const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, const geometry_msgs::Twist *start_vel, bool free_goal_vel=false)
Explore paths in new equivalence classes (e.g. homotopy classes) and initialize TEBs from them.
Definition: homotopy_class_planner.cpp:373
teb_local_planner::HomotopyClassPlanner::initial_plan_teb_
TebOptimalPlannerPtr initial_plan_teb_
Store pointer to the TEB related to the initial plan (use method getInitialPlanTEB() since it checks ...
Definition: homotopy_class_planner.h:591
teb_local_planner::HomotopyClassPlanner::cfg_
const TebConfig * cfg_
Config class that stores and manages all related parameters.
Definition: homotopy_class_planner.h:580
teb_local_planner::HomotopyClassPlanner::bestTebIdx
int bestTebIdx() const
find the index of the currently best TEB in the container
Definition: homotopy_class_planner.cpp:705
teb_local_planner::HomotopyClassPlanner::equivalence_classes_
EquivalenceClassContainer equivalence_classes_
Store all known quivalence classes (e.g. h-signatures) to allow checking for duplicates after finding...
Definition: homotopy_class_planner.h:595
teb_local_planner::TebConfig::HomotopyClasses::selection_alternative_time_cost
bool selection_alternative_time_cost
If true, time cost is replaced by the total transition time.
Definition: teb_config.h:194
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::ViaPointContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
Definition: optimal_planner.h:118
teb_local_planner::HomotopyClassPlanner::updateReferenceTrajectoryViaPoints
void updateReferenceTrajectoryViaPoints(bool all_trajectories)
Associate trajectories with via-points.
Definition: homotopy_class_planner.cpp:340
teb_local_planner::HomotopyClassPlanner::numTebsInClass
int numTebsInClass(const EquivalenceClassPtr &eq_class) const
Definition: homotopy_class_planner.cpp:431
teb_local_planner::HomotopyClassPlanner::findBestTeb
TebOptimalPlannerPtr findBestTeb()
In case of empty best teb, scores again the available plans to find the best one. The best_teb_ varia...
Definition: homotopy_class_planner.cpp:745
teb_local_planner::TebConfig::optim
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
teb_local_planner::TebConfig::Robot::max_vel_theta
double max_vel_theta
Maximum angular velocity of the robot.
Definition: teb_config.h:103
ros::Time::now
static Time now()


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