Go to the documentation of this file.
46 template<
typename B
idirIter,
typename Fun>
48 boost::optional<TimeDiffSequence::iterator> timediff_start, boost::optional<TimeDiffSequence::iterator> timediff_end)
52 HSignature3d* H =
new HSignature3d(*
cfg_);
53 H->calculateHSignature(path_start, path_end, fun_cplx_point,
obstacles, timediff_start, timediff_end);
58 HSignature* H =
new HSignature(*
cfg_);
59 H->calculateHSignature(path_start, path_end, fun_cplx_point,
obstacles);
65 template<
typename B
idirIter,
typename Fun>
75 candidate->setVelocityStart(*start_velocity);
78 candidate->teb().timediffs().begin(), candidate->teb().timediffs().end());
82 candidate->setVelocityGoalFree();
86 tebs_.push_back(candidate);
const ObstContainer * obstacles() const
Access current obstacle container (read-only)
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...
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
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....
boost::shared_ptr< TebOptimalPlanner > TebOptimalPlannerPtr
Abbrev. for shared instances of the TebOptimalPlanner.
double acc_lim_theta
Maximum angular acceleration of the robot.
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.
struct teb_local_planner::TebConfig::Trajectory trajectory
Trajectory 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
struct teb_local_planner::TebConfig::Robot robot
Robot related parameters.
boost::shared_ptr< EquivalenceClass > EquivalenceClassPtr
bool allow_init_with_backwards_motion
If true, the underlying trajectories might be initialized with backwards motions in case the goal is ...
double max_vel_x
Maximum translational velocity of the robot.
struct teb_local_planner::TebConfig::Obstacles obstacles
Obstacle related parameters.
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)
double acc_lim_x
Maximum translational acceleration of the robot.
bool include_dynamic_obstacles
Specify whether the movement of dynamic obstacles should be predicted by a constant velocity model (t...
const TebConfig * cfg_
Config class that stores and manages all 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