53 initialize(cfg, obstacles, robot_model, visual, via_points);
93 PoseSE2 start(initial_plan.front().pose);
94 PoseSE2 goal(initial_plan.back().pose);
96 return plan(start, goal, start_vel, free_goal_vel);
105 return plan(start_pose, goal_pose, start_vel, free_goal_vel);
141 return best_teb->getVelocityCommand(vx, vy, omega);
164 if (best_teb->teb().sizePoses() > 0)
176 else ROS_DEBUG(
"Ignoring HomotopyClassPlanner::visualize() call, since no visualization class was instantiated before.");
186 if (eq_class->isEqual(*eqrel.first))
197 if (!eq_class->isValid())
199 ROS_WARN(
"HomotopyClassPlanner: Ignoring invalid H-signature");
222 TebOptPlannerContainer::iterator it_teb =
tebs_.begin();
223 while(it_teb !=
tebs_.end())
226 if (delete_detours &&
tebs_.size()>1 && it_teb->get()->teb().detectDetoursBackwards(-0.1))
228 it_teb =
tebs_.erase(it_teb);
234 it_teb->get()->teb().timediffs().begin(), it_teb->get()->teb().timediffs().end());
243 it_teb =
tebs_.erase(it_teb);
303 ROS_ERROR(
"HomotopyClassPlanner::updateReferenceTrajectoryWithViaPoints(): Number of h-signatures does not match number of trajectories.");
307 if (all_trajectories)
323 tebs_[i]->setViaPoints(NULL);
357 candidate->setVelocityStart(*start_velocity);
360 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
364 tebs_.push_back(candidate);
380 candidate->setVelocityStart(*start_velocity);
384 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
388 tebs_.push_back(candidate);
402 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
408 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
410 it_teb->get()->teb().updateAndPruneTEB(*start, *goal);
412 it_teb->get()->setVelocityStart(*start_velocity);
422 boost::thread_group teb_threads;
423 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
429 teb_threads.join_all();
433 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
443 TebOptPlannerContainer::iterator it_teb =
tebs_.begin();
448 ROS_ERROR(
"HomotopyClassPlanner::deleteTebDetours(): number of equivalence classes (%lu) and trajectories (%lu) does not match.",
equivalence_classes_.size(),
tebs_.size());
454 while(it_teb !=
tebs_.end())
458 if (!it_eqclasses->second)
461 if (
tebs_.size()>1 && (it_teb->get()->teb().detectDetoursBackwards(threshold) || !it_eqclasses->first->isReasonable()))
463 it_teb =
tebs_.erase(it_teb);
471 if (!it_teb->get()->isOptimized())
473 it_teb =
tebs_.erase(it_teb);
476 ROS_DEBUG(
"HomotopyClassPlanner::deleteTebDetours(): removing candidate that was not optimized successfully");
498 ROS_DEBUG(
"initial teb not found, trying to find a match according to the cached equivalence class");
523 ROS_ERROR(
"HomotopyClassPlanner::getInitialPlanTEB(): number of equivalence classes (%lu) and number of trajectories (%lu) does not match.",
equivalence_classes_.size(),
tebs_.size());
526 ROS_DEBUG(
"HomotopyClassPlanner::getInitialPlanTEB(): initial TEB not found in the set of available trajectories.");
533 double min_cost = std::numeric_limits<double>::max();
534 double min_cost_last_best = std::numeric_limits<double>::max();
535 double min_cost_initial_plan_teb = std::numeric_limits<double>::max();
548 last_best_teb.reset();
551 if (initial_plan_teb)
560 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
571 if (*it_teb == last_best_teb)
572 teb_cost = min_cost_last_best;
573 else if (*it_teb == initial_plan_teb)
574 teb_cost = min_cost_initial_plan_teb;
576 teb_cost = it_teb->get()->getCurrentCost();
578 if (teb_cost < min_cost)
617 if (last_best_teb &&
best_teb_ != last_best_teb)
626 ROS_DEBUG(
"HomotopyClassPlanner::selectBestTeb(): Switching equivalence classes blocked (check parameter switching_blocking_period.");
639 if (
tebs_.size() == 1)
646 for (TebOptPlannerContainer::const_iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb, ++idx)
655 double inscribed_radius,
double circumscribed_radius,
int look_ahead_idx)
661 return best->isTrajectoryFeasible(costmap_model,footprint_spec, inscribed_radius, circumscribed_radius, look_ahead_idx);
667 for (TebOptPlannerContainer::const_iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
669 (*it_teb)->setPreferredTurningDir(dir);
679 return best->isHorizonReductionAppropriate(initial_plan);
684 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
686 it_teb->get()->computeCurrentCost(cost, obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
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, ...)
HomotopyClassPlanner()
Default constructor.
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
double min_obstacle_dist
Minimum desired separation from obstacles.
Eigen::Vector2d & position()
Access the 2D position part.
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.
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.
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...
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
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...
bool enable_multithreading
Activate multiple threading for planning multiple trajectories in parallel.
void deleteTebDetours(double threshold=0.0)
Check all available trajectories (TEBs) for detours and delete found ones.
RotType
Symbols for left/none/right rotations.
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 ...
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.
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.
bool simple_exploration
If true, distinctive trajectories are explored using a simple left-right approach (pass each obstacle...
double selection_cost_hysteresis
Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in...
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...
double selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the 'best' candidate.
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
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...
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
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.
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...
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 'best' candidate.
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
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.
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
int min_samples
Minimum number of samples (should be always greater than 2)
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.
double selection_prefer_initial_plan
Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the ini...