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  initialized_ = true;
74 
75  setVisualization(visual);
76 }
77 
78 
80 {
81  visualization_ = visualization;
82 }
83 
84 
85 
86 bool HomotopyClassPlanner::plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
87 {
88  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
89 
90  // store initial plan for further initializations (must be valid for the lifetime of this object or clearPlanner() is called!)
91  initial_plan_ = &initial_plan;
92 
93  PoseSE2 start(initial_plan.front().pose);
94  PoseSE2 goal(initial_plan.back().pose);
95 
96  return plan(start, goal, start_vel, free_goal_vel);
97 }
98 
99 
100 bool HomotopyClassPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
101 {
102  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
103  PoseSE2 start_pose(start);
104  PoseSE2 goal_pose(goal);
105  return plan(start_pose, goal_pose, start_vel, free_goal_vel);
106 }
107 
108 bool HomotopyClassPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
109 {
110  ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
111 
112  // Update old TEBs with new start, goal and velocity
113  updateAllTEBs(&start, &goal, start_vel);
114 
115  // Init new TEBs based on newly explored homotopy classes
117  // update via-points if activated
119  // Optimize all trajectories in alternative homotopy classes
121  // Delete any detours
122  deleteTebDetours(-0.1);
123  // Select which candidate (based on alternative homotopy classes) should be used
124  selectBestTeb();
125 
126  initial_plan_ = nullptr; // clear pointer to any previous initial plan (any previous plan is useless regarding the h-signature);
127  return true;
128 }
129 
130 bool HomotopyClassPlanner::getVelocityCommand(double& vx, double& vy, double& omega) const
131 {
132  TebOptimalPlannerConstPtr best_teb = bestTeb();
133  if (!best_teb)
134  {
135  vx = 0;
136  vy = 0;
137  omega = 0;
138  return false;
139  }
140 
141  return best_teb->getVelocityCommand(vx, vy, omega);
142 }
143 
144 
145 
146 
148 {
149  if (visualization_)
150  {
151  // Visualize graph
153  visualization_->publishGraph(graph_search_->graph_);
154 
155  // Visualize active tebs as marker
156  visualization_->publishTebContainer(tebs_);
157 
158  // Visualize best teb and feedback message if desired
159  TebOptimalPlannerConstPtr best_teb = bestTeb();
160  if (best_teb)
161  {
162  visualization_->publishLocalPlanAndPoses(best_teb->teb());
163 
164  if (best_teb->teb().sizePoses() > 0) //TODO maybe store current pose (start) within plan method as class field.
165  visualization_->publishRobotFootprintModel(best_teb->teb().Pose(0), *robot_model_);
166 
167  // feedback message
169  {
170  int best_idx = bestTebIdx();
171  if (best_idx>=0)
172  visualization_->publishFeedbackMessage(tebs_, (unsigned int) best_idx, *obstacles_);
173  }
174  }
175  }
176  else ROS_DEBUG("Ignoring HomotopyClassPlanner::visualize() call, since no visualization class was instantiated before.");
177 }
178 
179 
180 
182 {
183  // iterate existing h-signatures and check if there is an existing H-Signature similar the candidate
184  for (const std::pair<EquivalenceClassPtr, bool>& eqrel : equivalence_classes_)
185  {
186  if (eq_class->isEqual(*eqrel.first))
187  return true; // Found! Homotopy class already exists, therefore nothing added
188  }
189  return false;
190 }
191 
193 {
194  if (!eq_class)
195  return false;
196 
197  if (!eq_class->isValid())
198  {
199  ROS_WARN("HomotopyClassPlanner: Ignoring invalid H-signature");
200  return false;
201  }
202 
203  if (hasEquivalenceClass(eq_class))
204  return false;
205 
206  // Homotopy class not found -> Add to class-list, return that the h-signature is new
207  equivalence_classes_.push_back(std::make_pair(eq_class,lock));
208  return true;
209 }
210 
211 
213 {
214  // clear old h-signatures (since they could be changed due to new obstacle positions.
215  equivalence_classes_.clear();
216 
217  // Collect h-signatures for all existing TEBs and store them together with the corresponding iterator / pointer:
218 // typedef std::list< std::pair<TebOptPlannerContainer::iterator, std::complex<long double> > > TebCandidateType;
219 // TebCandidateType teb_candidates;
220 
221  // get new homotopy classes and delete multiple TEBs per homotopy class
222  TebOptPlannerContainer::iterator it_teb = tebs_.begin();
223  while(it_teb != tebs_.end())
224  {
225  // delete Detours if there is at least one other TEB candidate left in the container
226  if (delete_detours && tebs_.size()>1 && it_teb->get()->teb().detectDetoursBackwards(-0.1))
227  {
228  it_teb = tebs_.erase(it_teb); // delete candidate and set iterator to the next valid candidate
229  continue;
230  }
231 
232  // calculate equivalence class for the current candidate
233  EquivalenceClassPtr equivalence_class = calculateEquivalenceClass(it_teb->get()->teb().poses().begin(), it_teb->get()->teb().poses().end(), getCplxFromVertexPosePtr , obstacles_,
234  it_teb->get()->teb().timediffs().begin(), it_teb->get()->teb().timediffs().end());
235 
236 // teb_candidates.push_back(std::make_pair(it_teb,H));
237 
238  // WORKAROUND until the commented code below works
239  // Here we do not compare cost values. Just first come first serve...
240  bool new_flag = addEquivalenceClassIfNew(equivalence_class);
241  if (!new_flag)
242  {
243  it_teb = tebs_.erase(it_teb);
244  continue;
245  }
246 
247  ++it_teb;
248  }
249 
250  // Find multiple candidates and delete the one with higher cost
251  // TODO: this code needs to be adpated. Erasing tebs from the teb container_ could make iteratores stored in the candidate list invalid!
252 // TebCandidateType::reverse_iterator cand_i = teb_candidates.rbegin();
253 // int test_idx = 0;
254 // while (cand_i != teb_candidates.rend())
255 // {
256 //
257 // TebCandidateType::reverse_iterator cand_j = std::find_if(boost::next(cand_i),teb_candidates.rend(), boost::bind(compareH,_1,cand_i->second));
258 // if (cand_j != teb_candidates.rend() && cand_j != cand_i)
259 // {
260 // TebOptimalPlannerPtr pt1 = *(cand_j->first);
261 // TebOptimalPlannerPtr pt2 = *(cand_i->first);
262 // assert(pt1);
263 // assert(pt2);
264 // if ( cand_j->first->get()->getCurrentCost().sum() > cand_i->first->get()->getCurrentCost().sum() )
265 // {
266 // // found one that has higher cost, therefore erase cand_j
267 // tebs_.erase(cand_j->first);
268 // teb_candidates.erase(cand_j);
269 // }
270 // else // otherwise erase cand_i
271 // {
272 // tebs_.erase(cand_i->first);
273 // cand_i = teb_candidates.erase(cand_i);
274 // }
275 // }
276 // else
277 // {
278 // ROS_WARN_STREAM("increase cand_i");
279 // ++cand_i;
280 // }
281 // }
282 
283  // now add the h-signatures to the internal lookup-table (but only if there is no existing duplicate)
284 // for (TebCandidateType::iterator cand=teb_candidates.begin(); cand!=teb_candidates.end(); ++cand)
285 // {
286 // bool new_flag = addNewHSignatureIfNew(cand->second, cfg_->hcp.h_signature_threshold);
287 // if (!new_flag)
288 // {
289 // // ROS_ERROR_STREAM("getAndFilterHomotopyClassesTEB() - This schould not be happen.");
290 // tebs_.erase(cand->first);
291 // }
292 // }
293 
294 }
295 
297 {
298  if ( (!all_trajectories && !initial_plan_) || !via_points_ || via_points_->empty() || cfg_->optim.weight_viapoint <= 0)
299  return;
300 
301  if(equivalence_classes_.size() < tebs_.size())
302  {
303  ROS_ERROR("HomotopyClassPlanner::updateReferenceTrajectoryWithViaPoints(): Number of h-signatures does not match number of trajectories.");
304  return;
305  }
306 
307  if (all_trajectories)
308  {
309  // enable via-points for all tebs
310  for (std::size_t i=0; i < equivalence_classes_.size(); ++i)
311  {
312  tebs_[i]->setViaPoints(via_points_);
313  }
314  }
315  else
316  {
317  // enable via-points for teb in the same hommotopy class as the initial_plan and deactivate it for all other ones
318  for (std::size_t i=0; i < equivalence_classes_.size(); ++i)
319  {
320  if(initial_plan_eq_class_->isEqual(*equivalence_classes_[i].first))
321  tebs_[i]->setViaPoints(via_points_);
322  else
323  tebs_[i]->setViaPoints(NULL);
324  }
325  }
326 }
327 
328 
329 void HomotopyClassPlanner::exploreEquivalenceClassesAndInitTebs(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, const geometry_msgs::Twist* start_vel)
330 {
331  // first process old trajectories
332  renewAndAnalyzeOldTebs(false);
333 
334  // inject initial plan if available and not yet captured
335  if (initial_plan_)
336  {
338  }
339  else
340  {
341  initial_plan_teb_.reset();
342  initial_plan_teb_ = getInitialPlanTEB(); // this method searches for initial_plan_eq_class_ in the teb container (-> if !initial_plan_teb_)
343  }
344 
345  // now explore new homotopy classes and initialize tebs if new ones are found. The appropriate createGraph method is chosen via polymorphism.
346  graph_search_->createGraph(start,goal,dist_to_obst,cfg_->hcp.obstacle_heading_threshold, start_vel);
347 }
348 
349 
351 {
353 
354  candidate->teb().initTrajectoryToGoal(start, goal, 0, cfg_->robot.max_vel_x, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion);
355 
356  if (start_velocity)
357  candidate->setVelocityStart(*start_velocity);
358 
359  EquivalenceClassPtr H = calculateEquivalenceClass(candidate->teb().poses().begin(), candidate->teb().poses().end(), getCplxFromVertexPosePtr, obstacles_,
360  candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
361 
363  {
364  tebs_.push_back(candidate);
365  return tebs_.back();
366  }
367 
368  // If the candidate constitutes no new equivalence class, return a null pointer
369  return TebOptimalPlannerPtr();
370 }
371 
372 
373 TebOptimalPlannerPtr HomotopyClassPlanner::addAndInitNewTeb(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_velocity)
374 {
376 
377  candidate->teb().initTrajectoryToGoal(initial_plan, cfg_->robot.max_vel_x, true, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion);
378 
379  if (start_velocity)
380  candidate->setVelocityStart(*start_velocity);
381 
382  // store the h signature of the initial plan to enable searching a matching teb later.
383  initial_plan_eq_class_ = calculateEquivalenceClass(candidate->teb().poses().begin(), candidate->teb().poses().end(), getCplxFromVertexPosePtr, obstacles_,
384  candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
385 
386  if(addEquivalenceClassIfNew(initial_plan_eq_class_, true)) // also prevent candidate from deletion
387  {
388  tebs_.push_back(candidate);
389  return tebs_.back();
390  }
391 
392  // If the candidate constitutes no new equivalence class, return a null pointer
393  return TebOptimalPlannerPtr();
394 }
395 
396 void HomotopyClassPlanner::updateAllTEBs(const PoseSE2* start, const PoseSE2* goal, const geometry_msgs::Twist* start_velocity)
397 {
398  // If new goal is too far away, clear all existing trajectories to let them reinitialize later.
399  // Since all Tebs are sharing the same fixed goal pose, just take the first candidate:
400  if (!tebs_.empty() && (goal->position() - tebs_.front()->teb().BackPose().position()).norm() >= cfg_->trajectory.force_reinit_new_goal_dist)
401  {
402  ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
403  tebs_.clear();
404  equivalence_classes_.clear();
405  }
406 
407  // hot-start from previous solutions
408  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
409  {
410  it_teb->get()->teb().updateAndPruneTEB(*start, *goal);
411  if (start_velocity)
412  it_teb->get()->setVelocityStart(*start_velocity);
413  }
414 }
415 
416 
417 void HomotopyClassPlanner::optimizeAllTEBs(int iter_innerloop, int iter_outerloop)
418 {
419  // optimize TEBs in parallel since they are independend of each other
421  {
422  boost::thread_group teb_threads;
423  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
424  {
425  teb_threads.create_thread( boost::bind(&TebOptimalPlanner::optimizeTEB, it_teb->get(), iter_innerloop, iter_outerloop,
428  }
429  teb_threads.join_all();
430  }
431  else
432  {
433  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
434  {
435  it_teb->get()->optimizeTEB(iter_innerloop,iter_outerloop, true, cfg_->hcp.selection_obst_cost_scale,
436  cfg_->hcp.selection_viapoint_cost_scale, cfg_->hcp.selection_alternative_time_cost); // compute cost as well inside optimizeTEB (last argument = true)
437  }
438  }
439 }
440 
442 {
443  TebOptPlannerContainer::iterator it_teb = tebs_.begin();
444  EquivalenceClassContainer::iterator it_eqclasses = equivalence_classes_.begin();
445 
446  if (tebs_.size() != equivalence_classes_.size())
447  {
448  ROS_ERROR("HomotopyClassPlanner::deleteTebDetours(): number of equivalence classes (%lu) and trajectories (%lu) does not match.", equivalence_classes_.size(), tebs_.size());
449  return;
450  }
451 
452  bool modified;
453 
454  while(it_teb != tebs_.end())
455  {
456  modified = false;
457 
458  if (!it_eqclasses->second) // check if equivalence class is locked
459  {
460  // delete Detours if other TEBs will remain!
461  if (tebs_.size()>1 && (it_teb->get()->teb().detectDetoursBackwards(threshold) || !it_eqclasses->first->isReasonable()))
462  {
463  it_teb = tebs_.erase(it_teb);
464  it_eqclasses = equivalence_classes_.erase(it_eqclasses);
465  modified = true;
466  }
467  }
468 
469  // Also delete tebs that cannot be optimized (last optim call failed)
470  // here, we ignore the lock-state, since we cannot keep trajectories that are not optimizable
471  if (!it_teb->get()->isOptimized())
472  {
473  it_teb = tebs_.erase(it_teb);
474  it_eqclasses = equivalence_classes_.erase(it_eqclasses);
475  modified = true;
476  ROS_DEBUG("HomotopyClassPlanner::deleteTebDetours(): removing candidate that was not optimized successfully");
477  }
478 
479  if (!modified)
480  {
481  ++it_teb;
482  ++it_eqclasses;
483  }
484  }
485 }
486 
488 {
489  // first check stored teb object
490  if (initial_plan_teb_)
491  {
492  // check if the teb is still part of the teb container
493  if ( std::find(tebs_.begin(), tebs_.end(), initial_plan_teb_ ) != tebs_.end() )
494  return initial_plan_teb_;
495  else
496  {
497  initial_plan_teb_.reset(); // reset pointer for next call
498  ROS_DEBUG("initial teb not found, trying to find a match according to the cached equivalence class");
499  }
500  }
501 
502  // reset the locked state for equivalence classes // TODO: this might be adapted if not only the plan containing the initial plan is locked!
503  for (int i=0; i<equivalence_classes_.size(); ++i)
504  {
505  equivalence_classes_[i].second = false;
506  }
507 
508  // otherwise check if the stored reference equivalence class exist in the list of known classes
510  {
511  if (equivalence_classes_.size() == tebs_.size())
512  {
513  for (int i=0; i<equivalence_classes_.size(); ++i)
514  {
515  if (equivalence_classes_[i].first->isEqual(*initial_plan_eq_class_))
516  {
517  equivalence_classes_[i].second = true;
518  return tebs_[i];
519  }
520  }
521  }
522  else
523  ROS_ERROR("HomotopyClassPlanner::getInitialPlanTEB(): number of equivalence classes (%lu) and number of trajectories (%lu) does not match.", equivalence_classes_.size(), tebs_.size());
524  }
525  else
526  ROS_DEBUG("HomotopyClassPlanner::getInitialPlanTEB(): initial TEB not found in the set of available trajectories.");
527 
528  return TebOptimalPlannerPtr();
529 }
530 
532 {
533  double min_cost = std::numeric_limits<double>::max(); // maximum cost
534  double min_cost_last_best = std::numeric_limits<double>::max();
535  double min_cost_initial_plan_teb = std::numeric_limits<double>::max();
536  TebOptimalPlannerPtr last_best_teb;
537  TebOptimalPlannerPtr initial_plan_teb = getInitialPlanTEB();
538 
539  // check if last best_teb is still a valid candidate
540  if (best_teb_ && std::find(tebs_.begin(), tebs_.end(), best_teb_) != tebs_.end())
541  {
542  // get cost of this candidate
543  min_cost_last_best = best_teb_->getCurrentCost() * cfg_->hcp.selection_cost_hysteresis; // small hysteresis
544  last_best_teb = best_teb_;
545  }
546  else
547  {
548  last_best_teb.reset();
549  }
550 
551  if (initial_plan_teb) // the validity was already checked in getInitialPlanTEB()
552  {
553  // get cost of this candidate
554  min_cost_initial_plan_teb = initial_plan_teb->getCurrentCost() * cfg_->hcp.selection_prefer_initial_plan; // small hysteresis
555  }
556 
557 
558  best_teb_.reset(); // reset pointer
559 
560  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
561  {
562  // check if the related TEB leaves the local costmap region
563 // if (tebs_.size()>1 && !(*it_teb)->teb().isTrajectoryInsideRegion(20, -1, 1))
564 // {
565 // ROS_INFO("HomotopyClassPlanner::selectBestTeb(): skipping trajectories that are not inside the local costmap");
566 // continue;
567 // }
568 
569  double teb_cost;
570 
571  if (*it_teb == last_best_teb)
572  teb_cost = min_cost_last_best; // skip already known cost value of the last best_teb
573  else if (*it_teb == initial_plan_teb)
574  teb_cost = min_cost_initial_plan_teb;
575  else
576  teb_cost = it_teb->get()->getCurrentCost();
577 
578  if (teb_cost < min_cost)
579  {
580  // check if this candidate is currently not selected
581  best_teb_ = *it_teb;
582  min_cost = teb_cost;
583  }
584  }
585 
586 
587  // in case we haven't found any teb due to some previous checks, investigate list again
588 // if (!best_teb_ && !tebs_.empty())
589 // {
590 // ROS_DEBUG("all " << tebs_.size() << " tebs rejected previously");
591 // if (tebs_.size()==1)
592 // best_teb_ = tebs_.front();
593 // else // if multiple TEBs are available:
594 // {
595 // // try to use the one that relates to the initial plan
596 // TebOptimalPlannerPtr initial_plan_teb = getInitialPlanTEB();
597 // if (initial_plan_teb)
598 // best_teb_ = initial_plan_teb;
599 // else
600 // {
601 // // now compute the cost for the rest (we haven't computed it before)
602 // for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
603 // {
604 // double teb_cost = it_teb->get()->getCurrentCost();
605 // if (teb_cost < min_cost)
606 // {
607 // // check if this candidate is currently not selected
608 // best_teb_ = *it_teb;
609 // min_cost = teb_cost;
610 // }
611 // }
612 // }
613 // }
614 // }
615 
616  // check if we are allowed to change
617  if (last_best_teb && best_teb_ != last_best_teb)
618  {
619  ros::Time now = ros::Time::now();
621  {
623  }
624  else
625  {
626  ROS_DEBUG("HomotopyClassPlanner::selectBestTeb(): Switching equivalence classes blocked (check parameter switching_blocking_period.");
627  // block switching, so revert best_teb_
628  best_teb_ = last_best_teb;
629  }
630 
631  }
632 
633 
634  return best_teb_;
635 }
636 
638 {
639  if (tebs_.size() == 1)
640  return 0;
641 
642  if (!best_teb_)
643  return -1;
644 
645  int idx = 0;
646  for (TebOptPlannerContainer::const_iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb, ++idx)
647  {
648  if (*it_teb == best_teb_)
649  return idx;
650  }
651  return -1;
652 }
653 
654 bool HomotopyClassPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
655  double inscribed_radius, double circumscribed_radius, int look_ahead_idx)
656 {
657  TebOptimalPlannerPtr best = bestTeb();
658  if (!best)
659  return false;
660 
661  return best->isTrajectoryFeasible(costmap_model,footprint_spec, inscribed_radius, circumscribed_radius, look_ahead_idx);
662 }
663 
665 {
666  // set preferred turning dir for all TEBs
667  for (TebOptPlannerContainer::const_iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
668  {
669  (*it_teb)->setPreferredTurningDir(dir);
670  }
671 }
672 
673 bool HomotopyClassPlanner::isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const
674 {
675  TebOptimalPlannerPtr best = bestTeb();
676  if (!best)
677  return false;
678 
679  return best->isHorizonReductionAppropriate(initial_plan);
680 }
681 
682 void HomotopyClassPlanner::computeCurrentCost(std::vector<double>& cost, double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
683 {
684  for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
685  {
686  it_teb->get()->computeCurrentCost(cost, obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
687  }
688 }
689 
690 
691 } // end namespace
boost::shared_ptr< GraphSearchInterface > graph_search_
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, ...)
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:115
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:145
void exploreEquivalenceClassesAndInitTebs(const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, const geometry_msgs::Twist *start_vel)
Explore paths in new equivalence classes (e.g. homotopy classes) and initialize TEBs from them...
const ObstContainer * obstacles() const
Access current obstacle container (read-only)
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.
TebOptimalPlannerPtr bestTeb() const
Access current best trajectory candidate (that relates to the "best" homotopy class).
bool selection_alternative_time_cost
If true, time cost is replaced by the total transition time.
Definition: teb_config.h:173
bool initialized_
Keeps track about the correct initialization of this class.
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:183
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
TebOptimalPlannerPtr selectBestTeb()
In case of multiple, internally stored, alternative trajectories, select the best one according to th...
virtual bool isHorizonReductionAppropriate(const std::vector< geometry_msgs::PoseStamped > &initial_plan) const
Check if the planner suggests a shorter horizon (e.g. to resolve problems)
TebOptimalPlannerPtr initial_plan_teb_
Store pointer to the TEB related to the initial plan (use method getInitialPlanTEB() since it checks ...
TebOptimalPlannerPtr addAndInitNewTeb(BidirIter path_start, BidirIter path_end, Fun fun_position, double start_orientation, double goal_orientation, const geometry_msgs::Twist *start_velocity)
Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class...
virtual bool getVelocityCommand(double &vx, double &vy, double &omega) const
Get the velocity command from a previously optimized plan to control the robot at the current samplin...
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
#define ROS_WARN(...)
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:82
bool enable_multithreading
Activate multiple threading for planning multiple trajectories in parallel.
Definition: teb_config.h:166
void deleteTebDetours(double threshold=0.0)
Check all available trajectories (TEBs) for detours and delete found ones.
RotType
Symbols for left/none/right rotations.
Definition: misc.h:53
const TebConfig * cfg_
Config class that stores and manages all related parameters.
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:174
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.
#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:187
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:167
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:169
std::complex< long double > getCplxFromVertexPosePtr(const VertexPose *pose)
< Inline function used for calculateHSignature() in combination with VertexPose pointers ...
bool hasEquivalenceClass(const EquivalenceClassPtr &eq_class) const
Check if a h-signature exists already.
TebOptPlannerContainer tebs_
Container that stores multiple local teb planners (for alternative equivalence classes) and their cor...
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 selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the &#39;best&#39; candidate.
Definition: teb_config.h:172
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
Definition: teb_config.h:134
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:185
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
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...
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
Definition: teb_config.h:156
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:135
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:171
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
Definition: teb_config.h:84
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(...)
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).
int bestTebIdx() const
find the index of the currently best TEB in the container
double max_vel_x
Maximum translational velocity of the robot.
Definition: teb_config.h:90
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:170
#define ROS_DEBUG(...)


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 5 2019 19:25:10