Go to the documentation of this file.
72 std::random_device rd;
93 PoseSE2 goal(initial_plan.back().pose);
95 return plan(start, goal, start_vel, free_goal_vel);
138 return best_teb->getVelocityCommand(vx, vy, omega, look_ahead_poses);
161 if (best_teb->teb().sizePoses() > 0)
173 else ROS_DEBUG(
"Ignoring HomotopyClassPlanner::visualize() call, since no visualization class was instantiated before.");
183 if (eq_class->isEqual(*eqrel.first))
194 if (!eq_class->isValid())
196 ROS_WARN(
"HomotopyClassPlanner: Ignoring invalid H-signature");
221 bool has_best_teb = it_best_teb !=
tebs_.end();
224 std::iter_swap(
tebs_.begin(), it_best_teb);
235 TebOptPlannerContainer::iterator it_teb = has_best_teb ? std::next(
tebs_.begin(), 1) :
tebs_.begin();
236 while(it_teb !=
tebs_.end())
240 it_teb->get()->teb().timediffs().begin(), it_teb->get()->teb().timediffs().end());
249 it_teb =
tebs_.erase(it_teb);
311 ROS_ERROR(
"HomotopyClassPlanner::updateReferenceTrajectoryWithViaPoints(): Number of h-signatures does not match number of trajectories.");
315 if (all_trajectories)
331 tebs_[i]->setViaPoints(NULL);
368 candidate->setVelocityStart(*start_velocity);
371 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
374 candidate->setVelocityGoalFree();
378 tebs_.push_back(candidate);
400 if (eq_class->isEqual(*eqrel.first))
424 candidate->setVelocityStart(*start_velocity);
427 candidate->setVelocityGoalFree();
431 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
435 tebs_.push_back(candidate);
451 ROS_DEBUG(
"New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
457 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
459 it_teb->get()->teb().updateAndPruneTEB(*start, *goal);
461 it_teb->get()->setVelocityStart(*start_velocity);
474 boost::this_thread::disable_interruption di;
476 boost::thread_group teb_threads;
477 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
483 teb_threads.join_all();
487 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
506 ROS_DEBUG(
"initial teb not found, trying to find a match according to the cached equivalence class");
531 ROS_ERROR(
"HomotopyClassPlanner::getInitialPlanTEB(): number of equivalence classes (%lu) and number of trajectories (%lu) does not match.",
equivalence_classes_.size(),
tebs_.size());
534 ROS_DEBUG(
"HomotopyClassPlanner::getInitialPlanTEB(): initial TEB not found in the set of available trajectories.");
547 auto it_teb =
tebs_.begin();
553 it_teb =
tebs_.erase(it_teb);
566 double min_cost = std::numeric_limits<double>::max();
567 double min_cost_last_best = std::numeric_limits<double>::max();
568 double min_cost_initial_plan_teb = std::numeric_limits<double>::max();
583 if (initial_plan_teb)
592 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
604 teb_cost = min_cost_last_best;
605 else if (*it_teb == initial_plan_teb)
606 teb_cost = min_cost_initial_plan_teb;
608 teb_cost = it_teb->get()->getCurrentCost();
610 if (teb_cost < min_cost)
658 ROS_DEBUG(
"HomotopyClassPlanner::selectBestTeb(): Switching equivalence classes blocked (check parameter switching_blocking_period.");
671 if (
tebs_.size() == 1)
678 for (TebOptPlannerContainer::const_iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb, ++idx)
687 double inscribed_radius,
double circumscribed_radius,
int look_ahead_idx,
double feasibility_check_lookahead_distance)
689 bool feasible =
false;
695 ROS_ERROR(
"Couldn't retrieve the best plan");
698 feasible = best->isTrajectoryFeasible(costmap_model, footprint_spec, inscribed_radius, circumscribed_radius, look_ahead_idx, feasibility_check_lookahead_distance);
720 TebOptPlannerContainer::iterator return_iterator =
tebs_.end();
723 ROS_ERROR(
"removeTeb: size of eq classes != size of tebs");
724 return return_iterator;
727 for(
auto it =
tebs_.begin(); it !=
tebs_.end(); ++it)
731 return_iterator =
tebs_.erase(it);
737 return return_iterator;
743 for (TebOptPlannerContainer::const_iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
745 (*it_teb)->setPreferredTurningDir(dir);
760 for (TebOptPlannerContainer::iterator it_teb =
tebs_.begin(); it_teb !=
tebs_.end(); ++it_teb)
762 it_teb->get()->computeCurrentCost(cost, obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
767 const double len_orientation_vector)
774 double current_movement_orientation;
775 double best_plan_duration = std::max(
best_teb_->teb().getSumOfAllTimeDiffs(), 1.0);
778 for(
auto it_teb =
tebs_.begin(); it_teb !=
tebs_.end();)
785 if((*it_teb)->teb().sizePoses() < 2)
787 ROS_DEBUG(
"Discarding a plan with less than 2 poses");
791 double plan_orientation;
794 ROS_DEBUG(
"Failed to compute the start orientation for one of the tebs, likely close to the target");
798 if(fabs(g2o::normalize_theta(plan_orientation - current_movement_orientation)) > orient_threshold)
803 if(!it_teb->get()->isOptimized())
805 ROS_DEBUG(
"Removing a teb because it's not optimized");
811 ROS_DEBUG(
"Removing a teb because it's duration is much longer than that of the best teb");
823 bool second_pose_found =
false;
824 Eigen::Vector2d start_vector;
825 for(
auto& pose :
plan->teb().poses())
827 start_vector =
start_pose.position() - pose->position();
828 if(start_vector.norm() > len_orientation_vector)
830 second_pose_found =
true;
834 if(!second_pose_found)
836 orientation = std::atan2(start_vector[1], start_vector[0]);
const ObstContainer * obstacles() const
Access current obstacle container (read-only)
double switching_blocking_period
Specify a time duration in seconds that needs to be expired before a switch to new equivalence class ...
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 force_reinit_new_goal_angular
Reinitialize the trajectory if a previous goal is updated with an angular difference of more than the...
double weight_viapoint
Optimization weight for minimizing the distance to via-points.
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 isInBestTebClass(const EquivalenceClassPtr &eq_class) const
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).
TebOptimalPlannerPtr bestTeb() const
Access current best trajectory candidate (that relates to the "best" homotopy class).
ViaPointContainer via_points
virtual void visualize()
Publish the local plan, pose sequence and additional information via ros topics (e....
virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0)
Check whether the planned trajectory is feasible or not.
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 max_ratio_detours_duration_best_duration
Detours are discarted if their execution time / the execution time of the best teb is > this.
const ViaPointContainer * via_points_
Store the current list of via-points.
double selection_dropping_probability
At each planning cycle, TEBs other than the current 'best' one will be randomly dropped with this pro...
const std::vector< geometry_msgs::PoseStamped > * initial_plan_
Store the initial plan if available for a better trajectory initialization.
bool publish_feedback
Publish planner feedback containing the full trajectory and a list of active obstacles (should be ena...
ros::Time last_eq_class_switching_time_
Store the time at which the equivalence class changed recently.
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
bool hasDiverged() const override
Returns true if the planner has diverged.
bool simple_exploration
If true, distinctive trajectories are explored using a simple left-right approach (pass each obstacle...
struct teb_local_planner::TebConfig::HomotopyClasses hcp
int numTebsInBestTebClass() const
bool delete_detours_backwards
If enabled, the planner will discard the plans detouring backwards with respect to the best plan.
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....
EquivalenceClassPtr initial_plan_eq_class_
Store the equivalence class of the initial plan.
void initialize(const TebConfig &cfg, ObstContainer *obstacles=NULL, TebVisualizationPtr visualization=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL)
Initialize the HomotopyClassPlanner.
bool enable_multithreading
Activate multiple threading for planning multiple trajectories in parallel.
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 ...
RotType
Symbols for left/none/right rotations
int max_number_classes
Specify the maximum number of allowed alternative homotopy classes (limits computational effort)
int no_outer_iterations
Each outerloop iteration automatically resizes the trajectory and invokes the internal optimizer with...
TebOptimalPlannerPtr getInitialPlanTEB()
Returns a shared pointer to the TEB related to the initial plan.
TebVisualizationPtr visualization_
Instance of the visualization class (local/global plan, obstacles, ...)
int no_inner_iterations
Number of solver iterations called in each outerloop iteration.
boost::shared_ptr< TebOptimalPlanner > TebOptimalPlannerPtr
Abbrev. for shared instances of the TebOptimalPlanner.
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...
double selection_prefer_initial_plan
Specify a cost reduction in the interval (0,1) for the trajectory in the equivalence class of the ini...
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.
bool viapoints_all_candidates
If true, all trajectories of different topologies are attached to the current set of via-points,...
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.
TebVisualizationPtr visual
TebOptimalPlannerPtr last_best_teb_
Points to the plan used in the previous control cycle.
double length_start_orientation_vector
Length of the vector used to compute the start orientation of a plan.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory related parameters.
double min_obstacle_dist
Minimum desired separation from obstacles.
std::default_random_engine random_
double detours_orientation_tolerance
A plan is considered a detour if its start orientation differs more than this from the best plan.
bool global_plan_overwrite_orientation
Overwrite orientation of local subgoals provided by the global planner.
double & theta()
Access the orientation part (yaw angle) of the pose.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
std::complex< long double > getCplxFromVertexPosePtr(const VertexPose *pose)
< Inline function used for calculateHSignature() in combination with VertexPose pointers
Eigen::Vector2d & position()
Access the 2D position part.
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...
double selection_obst_cost_scale
Extra scaling of obstacle cost terms just for selecting the 'best' candidate.
#define ROS_ASSERT_MSG(cond,...)
bool hasEquivalenceClass(const EquivalenceClassPtr &eq_class) const
Check if a h-signature exists already.
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
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...
boost::shared_ptr< EquivalenceClass > EquivalenceClassPtr
double selection_cost_hysteresis
Specify how much trajectory cost must a new candidate have w.r.t. a previously selected trajectory in...
void updateAllTEBs(const PoseSE2 *start, const PoseSE2 *goal, const geometry_msgs::Twist *start_velocity)
Update TEBs with new pose, goal and current velocity.
double force_reinit_new_goal_dist
Reinitialize the trajectory if a previous goal is updated with a seperation of more than the specifie...
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
double selection_viapoint_cost_scale
Extra scaling of via-point cost terms just for selecting the 'best' candidate.
bool initialized_
Keeps track about the correct initialization of this class.
EquivalenceClassPtr best_teb_eq_class_
Store the equivalence class of the current best teb.
double obstacle_heading_threshold
Specify the value of the normalized scalar product between obstacle heading and goal heading in order...
HomotopyClassPlanner()
Default constructor.
double max_vel_x
Maximum translational velocity of the robot.
virtual ~HomotopyClassPlanner()
Destruct the HomotopyClassPlanner.
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
void setVisualization(TebVisualizationPtr visualization)
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and ...
TebOptPlannerContainer tebs_
Container that stores multiple local teb planners (for alternative equivalence classes) and their cor...
int min_samples
Minimum number of samples (should be always greater than 2)
TebOptPlannerContainer::iterator removeTeb(TebOptimalPlannerPtr &teb)
Removes the specified teb and the corresponding homotopy class from the list of available ones.
boost::shared_ptr< GraphSearchInterface > graph_search_
void randomlyDropTebs()
Randomly drop non-optimal TEBs to so we can explore other alternatives.
TebOptimalPlannerPtr best_teb_
Store the current best teb.
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
ROSCONSOLE_DECL void initialize()
void renewAndAnalyzeOldTebs(bool delete_detours)
Renew all found h-signatures for the new planning step based on existing TEBs. Optionally detours can...
bool visualize_hc_graph
Visualize the graph that is created for exploring new homotopy classes.
void optimizeAllTEBs(int iter_innerloop, int iter_outerloop)
Optimize all available trajectories by invoking the optimizer on each one.
RobotFootprintModelPtr robot_model
model of the robot's footprint
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.
TebOptimalPlannerPtr initial_plan_teb_
Store pointer to the TEB related to the initial plan (use method getInitialPlanTEB() since it checks ...
const TebConfig * cfg_
Config class that stores and manages all related parameters.
int bestTebIdx() const
find the index of the currently best TEB in the container
EquivalenceClassContainer equivalence_classes_
Store all known quivalence classes (e.g. h-signatures) to allow checking for duplicates after finding...
bool selection_alternative_time_cost
If true, time cost is replaced by the total transition time.
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
void updateReferenceTrajectoryViaPoints(bool all_trajectories)
Associate trajectories with via-points.
int numTebsInClass(const EquivalenceClassPtr &eq_class) const
TebOptimalPlannerPtr findBestTeb()
In case of empty best teb, scores again the available plans to find the best one. The best_teb_ varia...
struct teb_local_planner::TebConfig::Optimization optim
Optimization related parameters.
double max_vel_theta
Maximum angular velocity of the robot.
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15