53 initialize(cfg, obstacles, robot_model, visual, via_points);
73 std::random_device rd;
101 PoseSE2 goal(initial_plan.back().pose);
103 return plan(
start, goal, start_vel, free_goal_vel);
112 return plan(start_pose, goal_pose, start_vel, free_goal_vel);
146 return best_teb->getVelocityCommand(vx, vy, omega, look_ahead_poses);
169 if (best_teb->teb().sizePoses() > 0)
181 else ROS_DEBUG(
"Ignoring HomotopyClassPlanner::visualize() call, since no visualization class was instantiated before.");
191 if (eq_class->isEqual(*eqrel.first))
202 if (!eq_class->isValid())
204 ROS_WARN(
"HomotopyClassPlanner: Ignoring invalid H-signature");
229 bool has_best_teb = it_best_teb !=
tebs_.end();
232 std::iter_swap(
tebs_.begin(), it_best_teb);
243 TebOptPlannerContainer::iterator it_teb = has_best_teb ? std::next(
tebs_.begin(), 1) :
tebs_.begin();
244 while(it_teb !=
tebs_.end())
248 it_teb->get()->teb().timediffs().begin(), it_teb->get()->teb().timediffs().end());
257 it_teb =
tebs_.erase(it_teb);
319 ROS_ERROR(
"HomotopyClassPlanner::updateReferenceTrajectoryWithViaPoints(): Number of h-signatures does not match number of trajectories.");
323 if (all_trajectories)
339 tebs_[i]->setViaPoints(NULL);
376 candidate->setVelocityStart(*start_velocity);
379 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
382 candidate->setVelocityGoalFree();
386 tebs_.push_back(candidate);
408 if (eq_class->isEqual(*eqrel.first))
432 candidate->setVelocityStart(*start_velocity);
435 candidate->setVelocityGoalFree();
439 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
443 tebs_.push_back(candidate);
459 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
465 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
467 it_teb->get()->teb().updateAndPruneTEB(*start, *goal);
469 it_teb->get()->setVelocityStart(*start_velocity);
482 boost::this_thread::disable_interruption di;
484 boost::thread_group teb_threads;
485 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
491 teb_threads.join_all();
495 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
514 ROS_DEBUG(
"initial teb not found, trying to find a match according to the cached equivalence class");
539 ROS_ERROR(
"HomotopyClassPlanner::getInitialPlanTEB(): number of equivalence classes (%lu) and number of trajectories (%lu) does not match.",
equivalence_classes_.size(),
tebs_.size());
542 ROS_DEBUG(
"HomotopyClassPlanner::getInitialPlanTEB(): initial TEB not found in the set of available trajectories.");
555 auto it_teb =
tebs_.begin();
561 it_teb =
tebs_.erase(it_teb);
574 double min_cost = std::numeric_limits<double>::max();
575 double min_cost_last_best = std::numeric_limits<double>::max();
576 double min_cost_initial_plan_teb = std::numeric_limits<double>::max();
591 if (initial_plan_teb)
600 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
612 teb_cost = min_cost_last_best;
613 else if (*it_teb == initial_plan_teb)
614 teb_cost = min_cost_initial_plan_teb;
616 teb_cost = it_teb->get()->getCurrentCost();
618 if (teb_cost < min_cost)
666 ROS_DEBUG(
"HomotopyClassPlanner::selectBestTeb(): Switching equivalence classes blocked (check parameter switching_blocking_period.");
679 if (
tebs_.size() == 1)
686 for (TebOptPlannerContainer::const_iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb, ++idx)
695 double inscribed_radius,
double circumscribed_radius,
int look_ahead_idx)
697 bool feasible =
false;
703 ROS_ERROR(
"Couldn't retrieve the best plan");
706 feasible = best->isTrajectoryFeasible(costmap_model, footprint_spec, inscribed_radius, circumscribed_radius, look_ahead_idx);
728 TebOptPlannerContainer::iterator return_iterator =
tebs_.end();
731 ROS_ERROR(
"removeTeb: size of eq classes != size of tebs");
732 return return_iterator;
735 for(
auto it =
tebs_.begin(); it !=
tebs_.end(); ++it)
739 return_iterator =
tebs_.erase(it);
745 return return_iterator;
751 for (TebOptPlannerContainer::const_iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
753 (*it_teb)->setPreferredTurningDir(dir);
768 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
770 it_teb->get()->computeCurrentCost(cost, obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
775 const double len_orientation_vector)
782 double current_movement_orientation;
783 double best_plan_duration = std::max(
best_teb_->teb().getSumOfAllTimeDiffs(), 1.0);
786 for(
auto it_teb =
tebs_.begin(); it_teb !=
tebs_.end();)
793 if((*it_teb)->teb().sizePoses() < 2)
795 ROS_DEBUG(
"Discarding a plan with less than 2 poses");
799 double plan_orientation;
802 ROS_DEBUG(
"Failed to compute the start orientation for one of the tebs, likely close to the target");
806 if(fabs(g2o::normalize_theta(plan_orientation - current_movement_orientation)) > orient_threshold)
811 if(!it_teb->get()->isOptimized())
813 ROS_DEBUG(
"Removing a teb because it's not optimized");
819 ROS_DEBUG(
"Removing a teb because it's duration is much longer than that of the best teb");
831 bool second_pose_found =
false;
832 Eigen::Vector2d start_vector;
833 for(
auto& pose : plan->teb().poses())
835 start_vector = start_pose.
position() - pose->position();
836 if(start_vector.norm() > len_orientation_vector)
838 second_pose_found =
true;
842 if(!second_pose_found)
844 orientation = std::atan2(start_vector[1], start_vector[0]);
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, ...)
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.
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.
double force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
int numTebsInBestTebClass() const
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.
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.
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...
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...
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 ...
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...
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.
RotType
Symbols for left/none/right rotations.
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 ...
const ViaPointContainer * via_points_
Store the current list of via-points.
virtual ~HomotopyClassPlanner()
Destruct the HomotopyClassPlanner.
struct teb_local_planner::TebConfig::HomotopyClasses hcp
std::default_random_engine random_
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 'best' one will be randomly dropped with this pro...
#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 ...
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...
void updateRobotModel(RobotFootprintModelPtr robot_model)
double max_vel_theta
Maximum angular velocity of the robot.
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.
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...
double & theta()
Access the orientation part (yaw angle) of the pose.
double selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the 'best' candidate.
Eigen::Vector2d & position()
Access the 2D position part.
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
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...
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.
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
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.
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.
int max_number_classes
Specify the maximum number of allowed alternative homotopy classes (limits computational effort) ...
double max_ratio_detours_duration_best_duration
Detours are discarted if their execution time / the execution time of the best teb is > this...
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).
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...