46 template<
typename B
idirIter,
typename Fun>
48 boost::optional<TimeDiffSequence::iterator> timediff_start, boost::optional<TimeDiffSequence::iterator> timediff_end)
53 H->
calculateHSignature(path_start, path_end, fun_cplx_point, obstacles, timediff_start, timediff_end);
65 template<
typename B
idirIter,
typename Fun>
75 candidate->setVelocityStart(*start_velocity);
78 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
82 tebs_.push_back(candidate);
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
double acc_lim_x
Maximum translational acceleration of the robot.
The H-signature in three dimensions (here: x-y-t) defines an equivalence relation based on homology u...
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
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...
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.
The H-signature defines an equivalence relation based on homology in terms of complex calculus...
boost::shared_ptr< TebOptimalPlanner > TebOptimalPlannerPtr
Abbrev. for shared instances of the TebOptimalPlanner.
void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer *obstacles)
Calculate the H-Signature of a path.
RobotFootprintModelPtr robot_model_
Robot model shared instance.
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
double acc_lim_theta
Maximum angular acceleration of the robot.
const TebConfig * cfg_
Config class that stores and manages all related parameters.
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 ...
double max_vel_theta
Maximum angular velocity of the robot.
boost::shared_ptr< EquivalenceClass > EquivalenceClassPtr
void calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer *obstacles, boost::optional< TimeDiffSequence::iterator > timediff_start, boost::optional< TimeDiffSequence::iterator > timediff_end)
Calculate the H-Signature of a path.
TebOptPlannerContainer tebs_
Container that stores multiple local teb planners (for alternative equivalence classes) and their cor...
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...
bool include_dynamic_obstacles
Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (t...
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
int min_samples
Minimum number of samples (should be always greater than 2)
double max_vel_x
Maximum translational velocity of the robot.