Go to the documentation of this file.
39 #ifndef TIMED_ELASTIC_BAND_H_
40 #define TIMED_ELASTIC_BAND_H_
45 #include <geometry_msgs/PoseStamped.h>
46 #include <geometry_msgs/PoseArray.h>
86 class TimedElasticBand
235 void addPose(
const Eigen::Ref<const Eigen::Vector2d>& position,
double theta,
bool fixed=
false);
244 void addPose(
double x,
double y,
double theta,
bool fixed=
false);
270 void addPoseAndTimeDiff(
const Eigen::Ref<const Eigen::Vector2d>& position,
double theta,
double dt);
301 void insertPose(
int index,
const Eigen::Ref<const Eigen::Vector2d>& position,
double theta);
310 void insertPose(
int index,
double x,
double y,
double theta);
369 bool initTrajectoryToGoal(
const PoseSE2& start,
const PoseSE2& goal,
double diststep=0,
double max_vel_x=0.5,
int min_samples = 3,
bool guess_backwards_motion =
false);
406 template<
typename B
idirIter,
typename Fun>
407 bool initTrajectoryToGoal(BidirIter path_start, BidirIter path_end, Fun fun_position,
double max_vel_x,
double max_vel_theta,
408 boost::optional<double> max_acc_x, boost::optional<double> max_acc_theta,
409 boost::optional<double> start_orientation, boost::optional<double> goal_orientation,
int min_samples = 3,
bool guess_backwards_motion =
false);
427 bool initTrajectoryToGoal(
const std::vector<geometry_msgs::PoseStamped>& plan,
double max_vel_x,
double max_vel_theta,
bool estimate_orient=
false,
int min_samples = 3,
bool guess_backwards_motion =
false);
432 ROS_WARN_ONCE(
"initTEBtoGoal is deprecated and has been replaced by initTrajectoryToGoal. The signature has changed: timestep has been replaced by max_vel_x. \
433 this deprecated method sets max_vel_x = 1. Please update your code.");
434 return initTrajectoryToGoal(start, goal, diststep, timestep, min_samples, guess_backwards_motion);
437 template<
typename B
idirIter,
typename Fun>
438 ROS_DEPRECATED bool initTEBtoGoal(BidirIter path_start, BidirIter path_end, Fun fun_position,
double max_vel_x,
double max_vel_theta,
439 boost::optional<double> max_acc_x, boost::optional<double> max_acc_theta,
440 boost::optional<double> start_orientation, boost::optional<double> goal_orientation,
int min_samples = 3,
bool guess_backwards_motion =
false)
442 return initTrajectoryToGoal<BidirIter, Fun>(path_start, path_end, fun_position, max_vel_x, max_vel_theta,
443 max_acc_x, max_acc_theta, start_orientation, goal_orientation, min_samples, guess_backwards_motion);
446 ROS_DEPRECATED bool initTEBtoGoal(
const std::vector<geometry_msgs::PoseStamped>& plan,
double dt,
bool estimate_orient=
false,
int min_samples = 3,
bool guess_backwards_motion =
false)
448 ROS_WARN_ONCE(
"initTEBtoGoal is deprecated and has been replaced by initTrajectoryToGoal. The signature has changed: dt has been replaced by max_vel_x. \
449 this deprecated method sets max_vel = 1. Please update your code.");
450 return initTrajectoryToGoal(plan, 1.0, 1.0, estimate_orient, min_samples, guess_backwards_motion);
475 void updateAndPruneTEB(boost::optional<const PoseSE2&> new_start, boost::optional<const PoseSE2&> new_goal,
int min_samples = 3);
507 void autoResize(
double dt_ref,
double dt_hysteresis,
int min_samples = 3,
int max_samples=1000,
bool fast_mode=
false);
549 int findClosestTrajectoryPose(
const Eigen::Ref<const Eigen::Vector2d>& ref_point,
double* distance = NULL,
int begin_idx=0)
const;
565 int findClosestTrajectoryPose(
const Eigen::Ref<const Eigen::Vector2d>& ref_line_start,
const Eigen::Ref<const Eigen::Vector2d>& ref_line_end,
double* distance = NULL)
const;
649 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool isTrajectoryInsideRegion(double radius, double max_dist_behind_robot=-1, int skip_poses=0)
Check if all trajectory points are contained in a specific region.
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
std::vector< VertexTimeDiff * > TimeDiffSequence
Container of time differences that define the temporal of the trajectory.
void deleteTimeDiffs(int index, int number)
Delete multiple (number) time differences starting at pos. index in the timediff sequence.
TimeDiffSequence timediff_vec_
Internal container storing the sequence of optimzable timediff vertices.
double & TimeDiff(int index)
Access the time difference at pos index of the time sequence.
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
void insertTimeDiff(int index, double dt)
Insert a new timediff vertex at pos. index to the timediff sequence.
virtual ~TimedElasticBand()
Destruct the class.
#define ROS_WARN_ONCE(...)
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences)
void addPoseAndTimeDiff(const PoseSE2 &pose, double dt)
Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequenc...
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
void addTimeDiff(double dt, bool fixed=false)
Append a new time difference vertex to the back of the time diff sequence.
void addPose(const PoseSE2 &pose, bool fixed=false)
Append a new pose vertex to the back of the pose sequence.
int findClosestTrajectoryPose(const Eigen::Ref< const Eigen::Vector2d > &ref_point, double *distance=NULL, int begin_idx=0) const
Find the closest point on the trajectory w.r.t. to a provided reference point.
void setPoseVertexFixed(int index, bool status)
Set a pose vertex at pos index of the pose sequence to be fixed or unfixed during optimization.
PoseSequence & poses()
Access the complete pose sequence.
This class stores and wraps a time difference into a vertex that can be optimized via g2o.
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
void deletePoses(int index, int number)
Delete multiple (number) poses starting at pos. index in the pose sequence.
void updateAndPruneTEB(boost::optional< const PoseSE2 & > new_start, boost::optional< const PoseSE2 & > new_goal, int min_samples=3)
Hot-Start from an existing trajectory with updated start and goal poses.
void insertPose(int index, const PoseSE2 &pose)
Insert a new pose vertex at pos. index to the pose sequence.
ROS_DEPRECATED bool initTEBtoGoal(const PoseSE2 &start, const PoseSE2 &goal, double diststep=0, double timestep=1, int min_samples=3, bool guess_backwards_motion=false)
VertexPose * PoseVertex(int index)
Access the vertex of a pose at pos index for optimization purposes.
int sizePoses() const
Get the length of the internal pose sequence.
void deletePose(int index)
Delete pose at pos. index in the pose sequence.
double & BackTimeDiff()
Access the last TimeDiff in the time diff sequence.
bool initTrajectoryToGoal(const PoseSE2 &start, const PoseSE2 &goal, double diststep=0, double max_vel_x=0.5, int min_samples=3, bool guess_backwards_motion=false)
Initialize a trajectory between a given start and goal pose.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
TimeDiffSequence & timediffs()
Access the complete timediff sequence.
PoseSequence pose_vec_
Internal container storing the sequence of optimzable pose vertices.
std::vector< VertexPose * > PoseSequence
Container of poses that represent the spatial part of the trajectory.
double getAccumulatedDistance() const
Calculate the length (accumulated euclidean distance) of the trajectory.
void deleteTimeDiff(int index)
Delete pose at pos. index in the timediff sequence.
TimedElasticBand()
Construct the class.
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
void autoResize(double dt_ref, double dt_hysteresis, int min_samples=3, int max_samples=1000, bool fast_mode=false)
Resize the trajectory by removing or inserting a (pose,dt) pair depending on a reference temporal res...
void setTimeDiffVertexFixed(int index, bool status)
Set a timediff vertex at pos index of the timediff sequence to be fixed or unfixed during optimizatio...
VertexTimeDiff * TimeDiffVertex(int index)
Access the vertex of a time difference at pos index for optimization purposes.
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence)
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15