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


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