timed_elastic_band.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
39 #ifndef TIMED_ELASTIC_BAND_H_
40 #define TIMED_ELASTIC_BAND_H_
41 
42 #include <ros/ros.h>
43 #include <ros/assert.h>
44 
45 #include <geometry_msgs/PoseStamped.h>
46 #include <geometry_msgs/PoseArray.h>
47 #include <tf/tf.h>
48 
49 #include <complex>
50 #include <iterator>
51 
53 
54 // G2O Types
57 
58 
59 namespace teb_local_planner
60 {
61 
63 typedef std::vector<VertexPose*> PoseSequence;
65 typedef std::vector<VertexTimeDiff*> TimeDiffSequence;
66 
67 
86 class TimedElasticBand
87 {
88 public:
89 
94 
98  virtual ~TimedElasticBand();
99 
100 
101 
104 
109  PoseSequence& poses() {return pose_vec_;};
110 
115  const PoseSequence& poses() const {return pose_vec_;};
116 
122 
127  const TimeDiffSequence& timediffs() const {return timediff_vec_;};
128 
134  double& TimeDiff(int index)
135  {
136  ROS_ASSERT(index<sizeTimeDiffs());
137  return timediff_vec_.at(index)->dt();
138  }
139 
145  const double& TimeDiff(int index) const
146  {
147  ROS_ASSERT(index<sizeTimeDiffs());
148  return timediff_vec_.at(index)->dt();
149  }
150 
156  PoseSE2& Pose(int index)
157  {
158  ROS_ASSERT(index<sizePoses());
159  return pose_vec_.at(index)->pose();
160  }
161 
167  const PoseSE2& Pose(int index) const
168  {
169  ROS_ASSERT(index<sizePoses());
170  return pose_vec_.at(index)->pose();
171  }
172 
176  PoseSE2& BackPose() {return pose_vec_.back()->pose(); }
177 
181  const PoseSE2& BackPose() const {return pose_vec_.back()->pose();}
182 
186  double& BackTimeDiff() {return timediff_vec_.back()->dt(); }
187 
191  const double& BackTimeDiff() const {return timediff_vec_.back()->dt(); }
192 
198  VertexPose* PoseVertex(int index)
199  {
200  ROS_ASSERT(index<sizePoses());
201  return pose_vec_.at(index);
202  }
203 
209  VertexTimeDiff* TimeDiffVertex(int index)
210  {
211  ROS_ASSERT(index<sizeTimeDiffs());
212  return timediff_vec_.at(index);
213  }
214 
216 
217 
218 
221 
227  void addPose(const PoseSE2& pose, bool fixed=false);
228 
235  void addPose(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, bool fixed=false);
236 
244  void addPose(double x, double y, double theta, bool fixed=false);
245 
251  void addTimeDiff(double dt, bool fixed=false);
252 
261  void addPoseAndTimeDiff(const PoseSE2& pose, double dt);
262 
270  void addPoseAndTimeDiff(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, double dt);
271 
280  void addPoseAndTimeDiff(double x, double y, double theta, double dt);
281 
283 
284 
287 
293  void insertPose(int index, const PoseSE2& pose);
294 
301  void insertPose(int index, const Eigen::Ref<const Eigen::Vector2d>& position, double theta);
302 
310  void insertPose(int index, double x, double y, double theta);
311 
317  void insertTimeDiff(int index, double dt);
318 
323  void deletePose(int index);
324 
330  void deletePoses(int index, int number);
331 
336  void deleteTimeDiff(int index);
337 
343  void deleteTimeDiffs(int index, int number);
344 
346 
347 
350 
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);
370 
371 
406  template<typename BidirIter, 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);
410 
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);
428 
429 
430  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)
431  {
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);
435  }
436 
437  template<typename BidirIter, 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)
441  {
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);
444  }
445 
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)
447  {
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);
451  }
452 
453 
455 
458 
459 
475  void updateAndPruneTEB(boost::optional<const PoseSE2&> new_start, boost::optional<const PoseSE2&> new_goal, int min_samples = 3);
476 
477 
507  void autoResize(double dt_ref, double dt_hysteresis, int min_samples = 3, int max_samples=1000, bool fast_mode=false);
508 
514  void setPoseVertexFixed(int index, bool status);
515 
521  void setTimeDiffVertexFixed(int index, bool status);
522 
527  void clearTimedElasticBand();
528 
530 
531 
534 
549  int findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_point, double* distance = NULL, int begin_idx=0) const;
550 
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;
566 
580  int findClosestTrajectoryPose(const Point2dContainer& vertices, double* distance = NULL) const;
581 
593  int findClosestTrajectoryPose(const Obstacle& obstacle, double* distance = NULL) const;
594 
595 
599  int sizePoses() const {return (int)pose_vec_.size();};
600 
604  int sizeTimeDiffs() const {return (int)timediff_vec_.size();};
605 
609  bool isInit() const {return !timediff_vec_.empty() && !pose_vec_.empty();}
610 
614  double getSumOfAllTimeDiffs() const;
615 
621  double getSumOfTimeDiffsUpToIdx(int index) const;
622 
626  double getAccumulatedDistance() const;
627 
638  bool isTrajectoryInsideRegion(double radius, double max_dist_behind_robot=-1, int skip_poses=0);
639 
640 
641 
643 
644 protected:
647 
648 public:
649  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
650 };
651 
652 } // namespace teb_local_planner
653 
654 
655 // include template implementations / definitions
657 
658 
659 #endif /* TIMED_ELASTIC_BAND_H_ */
teb_local_planner::TimedElasticBand::isTrajectoryInsideRegion
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.
Definition: timed_elastic_band.cpp:636
teb_local_planner::TimedElasticBand::Pose
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
Definition: timed_elastic_band.h:192
teb_local_planner::TimeDiffSequence
std::vector< VertexTimeDiff * > TimeDiffSequence
Container of time differences that define the temporal of the trajectory.
Definition: timed_elastic_band.h:101
teb_local_planner::TimedElasticBand::deleteTimeDiffs
void deleteTimeDiffs(int index, int number)
Delete multiple (number) time differences starting at pos. index in the timediff sequence.
Definition: timed_elastic_band.cpp:205
teb_local_planner::TimedElasticBand::timediff_vec_
TimeDiffSequence timediff_vec_
Internal container storing the sequence of optimzable timediff vertices.
Definition: timed_elastic_band.h:682
timed_elastic_band.hpp
ros.h
teb_local_planner::TimedElasticBand::TimeDiff
double & TimeDiff(int index)
Access the time difference at pos index of the time sequence.
Definition: timed_elastic_band.h:170
teb_local_planner::Point2dContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
Definition: distance_calculations.h:86
teb_local_planner::TimedElasticBand::insertTimeDiff
void insertTimeDiff(int index, double dt)
Insert a new timediff vertex at pos. index to the timediff sequence.
Definition: timed_elastic_band.cpp:231
teb_local_planner::TimedElasticBand::~TimedElasticBand
virtual ~TimedElasticBand()
Destruct the class.
Definition: timed_elastic_band.cpp:109
ROS_WARN_ONCE
#define ROS_WARN_ONCE(...)
teb_local_planner::TimedElasticBand::isInit
bool isInit() const
Check whether the trajectory is initialized (nonzero pose and timediff sequences)
Definition: timed_elastic_band.h:645
teb_local_planner::TimedElasticBand::addPoseAndTimeDiff
void addPoseAndTimeDiff(const PoseSE2 &pose, double dt)
Append a (pose, timediff) vertex pair to the end of the current trajectory (pose and timediff sequenc...
Definition: timed_elastic_band.cpp:160
teb_local_planner::TimedElasticBand::BackPose
PoseSE2 & BackPose()
Access the last PoseSE2 in the pose sequence.
Definition: timed_elastic_band.h:212
teb_local_planner::TimedElasticBand::addTimeDiff
void addTimeDiff(double dt, bool fixed=false)
Append a new time difference vertex to the back of the time diff sequence.
Definition: timed_elastic_band.cpp:137
ROS_DEPRECATED
#define ROS_DEPRECATED
teb_local_planner::TimedElasticBand::addPose
void addPose(const PoseSE2 &pose, bool fixed=false)
Append a new pose vertex to the back of the pose sequence.
Definition: timed_elastic_band.cpp:116
teb_local_planner::TimedElasticBand::findClosestTrajectoryPose
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.
Definition: timed_elastic_band.cpp:491
teb_local_planner::TimedElasticBand::setPoseVertexFixed
void setPoseVertexFixed(int index, bool status)
Set a pose vertex at pos index of the pose sequence to be fixed or unfixed during optimization.
Definition: timed_elastic_band.cpp:250
teb_local_planner::TimedElasticBand::poses
PoseSequence & poses()
Access the complete pose sequence.
Definition: timed_elastic_band.h:145
teb_local_planner::VertexTimeDiff
This class stores and wraps a time difference into a vertex that can be optimized via g2o.
Definition: vertex_timediff.h:102
teb_local_planner::TimedElasticBand::getSumOfTimeDiffsUpToIdx
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
Definition: timed_elastic_band.cpp:336
obstacles.h
teb_local_planner::TimedElasticBand::deletePoses
void deletePoses(int index, int number)
Delete multiple (number) poses starting at pos. index in the pose sequence.
Definition: timed_elastic_band.cpp:190
teb_local_planner::TimedElasticBand::updateAndPruneTEB
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.
Definition: timed_elastic_band.cpp:591
teb_local_planner::TimedElasticBand::insertPose
void insertPose(int index, const PoseSE2 &pose)
Insert a new pose vertex at pos. index to the pose sequence.
Definition: timed_elastic_band.cpp:213
vertex_timediff.h
teb_local_planner::TimedElasticBand::initTEBtoGoal
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)
Definition: timed_elastic_band.h:466
teb_local_planner::TimedElasticBand::PoseVertex
VertexPose * PoseVertex(int index)
Access the vertex of a pose at pos index for optimization purposes.
Definition: timed_elastic_band.h:234
teb_local_planner::TimedElasticBand::sizePoses
int sizePoses() const
Get the length of the internal pose sequence.
Definition: timed_elastic_band.h:635
export_to_svg.vertices
list vertices
Definition: export_to_svg.py:233
teb_local_planner::TimedElasticBand::deletePose
void deletePose(int index)
Delete pose at pos. index in the pose sequence.
Definition: timed_elastic_band.cpp:183
teb_local_planner::TimedElasticBand::BackTimeDiff
double & BackTimeDiff()
Access the last TimeDiff in the time diff sequence.
Definition: timed_elastic_band.h:222
tf.h
teb_local_planner::TimedElasticBand::initTrajectoryToGoal
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.
Definition: timed_elastic_band.cpp:361
teb_local_planner::PoseSE2
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:93
teb_local_planner::TimedElasticBand::sizeTimeDiffs
int sizeTimeDiffs() const
Get the length of the internal timediff sequence.
Definition: timed_elastic_band.h:640
teb_local_planner::TimedElasticBand::timediffs
TimeDiffSequence & timediffs()
Access the complete timediff sequence.
Definition: timed_elastic_band.h:157
vertex_pose.h
teb_local_planner::TimedElasticBand::pose_vec_
PoseSequence pose_vec_
Internal container storing the sequence of optimzable pose vertices.
Definition: timed_elastic_band.h:681
teb_local_planner::PoseSequence
std::vector< VertexPose * > PoseSequence
Container of poses that represent the spatial part of the trajectory.
Definition: timed_elastic_band.h:99
teb_local_planner::TimedElasticBand::getAccumulatedDistance
double getAccumulatedDistance() const
Calculate the length (accumulated euclidean distance) of the trajectory.
Definition: timed_elastic_band.cpp:350
teb_local_planner::TimedElasticBand::deleteTimeDiff
void deleteTimeDiff(int index)
Delete pose at pos. index in the timediff sequence.
Definition: timed_elastic_band.cpp:198
teb_local_planner::TimedElasticBand::TimedElasticBand
TimedElasticBand()
Construct the class.
Definition: timed_elastic_band.cpp:105
assert.h
ROS_ASSERT
#define ROS_ASSERT(cond)
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::VertexPose
This class stores and wraps a SE2 pose (position and orientation) into a vertex that can be optimized...
Definition: vertex_pose.h:104
teb_local_planner::TimedElasticBand::clearTimedElasticBand
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
Definition: timed_elastic_band.cpp:238
teb_local_planner::TimedElasticBand::autoResize
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...
Definition: timed_elastic_band.cpp:263
teb_local_planner::TimedElasticBand::setTimeDiffVertexFixed
void setTimeDiffVertexFixed(int index, bool status)
Set a timediff vertex at pos index of the timediff sequence to be fixed or unfixed during optimizatio...
Definition: timed_elastic_band.cpp:256
teb_local_planner::TimedElasticBand::TimeDiffVertex
VertexTimeDiff * TimeDiffVertex(int index)
Access the vertex of a time difference at pos index for optimization purposes.
Definition: timed_elastic_band.h:245
teb_local_planner::TimedElasticBand::getSumOfAllTimeDiffs
double getSumOfAllTimeDiffs() const
Calculate the total transition time (sum over all time intervals of the timediff sequence)
Definition: timed_elastic_band.cpp:325


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15