timed_elastic_band.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016,
00006  *  TU Dortmund - Institute of Control Theory and Systems Engineering.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the institute nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * Author: Christoph Rösmann
00037  *********************************************************************/
00038 
00039 #ifndef TIMED_ELASTIC_BAND_H_
00040 #define TIMED_ELASTIC_BAND_H_
00041 
00042 #include <ros/ros.h>
00043 #include <ros/assert.h>
00044 
00045 #include <geometry_msgs/PoseStamped.h>
00046 #include <geometry_msgs/PoseArray.h>
00047 #include <tf/tf.h>
00048 
00049 #include <complex>
00050 #include <iterator>
00051 
00052 #include <teb_local_planner/obstacles.h>
00053 
00054 // G2O Types
00055 #include <teb_local_planner/g2o_types/vertex_pose.h>
00056 #include <teb_local_planner/g2o_types/vertex_timediff.h>
00057 
00058 
00059 namespace teb_local_planner
00060 {
00061 
00063 typedef std::vector<VertexPose*> PoseSequence;
00065 typedef std::vector<VertexTimeDiff*> TimeDiffSequence;
00066 
00067 
00086 class TimedElasticBand
00087 {
00088 public:
00089 
00093   TimedElasticBand();
00094   
00098   virtual ~TimedElasticBand();
00099 
00100   
00101   
00104   
00109   PoseSequence& poses() {return pose_vec_;};
00110   
00115   const PoseSequence& poses() const {return pose_vec_;};
00116   
00121   TimeDiffSequence& timediffs() {return timediff_vec_;};
00122   
00127   const TimeDiffSequence& timediffs() const {return timediff_vec_;};  
00128   
00134   double& TimeDiff(int index)
00135   {
00136     ROS_ASSERT(index<sizeTimeDiffs()); 
00137     return timediff_vec_.at(index)->dt();
00138   }
00139   
00145   const double& TimeDiff(int index) const
00146   {
00147     ROS_ASSERT(index<sizeTimeDiffs()); 
00148     return timediff_vec_.at(index)->dt();
00149   }
00150   
00156   PoseSE2& Pose(int index) 
00157   {
00158     ROS_ASSERT(index<sizePoses());
00159     return pose_vec_.at(index)->pose();
00160   }
00161   
00167   const PoseSE2& Pose(int index) const 
00168   {
00169     ROS_ASSERT(index<sizePoses());
00170     return pose_vec_.at(index)->pose();
00171   }
00172   
00176   PoseSE2& BackPose() {return pose_vec_.back()->pose(); }
00177   
00181   const PoseSE2& BackPose() const {return pose_vec_.back()->pose();}
00182   
00186   double& BackTimeDiff() {return timediff_vec_.back()->dt(); }
00187   
00191   const double& BackTimeDiff() const {return timediff_vec_.back()->dt(); }
00192   
00198   VertexPose* PoseVertex(int index) 
00199   {
00200     ROS_ASSERT(index<sizePoses());
00201     return pose_vec_.at(index);
00202   }
00203   
00209   VertexTimeDiff* TimeDiffVertex(int index) 
00210   {
00211     ROS_ASSERT(index<sizeTimeDiffs()); 
00212     return timediff_vec_.at(index);
00213   }
00214   
00216   
00217   
00218   
00221   
00227   void addPose(const PoseSE2& pose, bool fixed=false);  
00228 
00235   void addPose(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, bool fixed=false);
00236   
00244   void addPose(double x, double y, double theta, bool fixed=false);
00245   
00251   void addTimeDiff(double dt, bool fixed=false);
00252   
00261   void addPoseAndTimeDiff(const PoseSE2& pose, double dt);
00262   
00270   void addPoseAndTimeDiff(const Eigen::Ref<const Eigen::Vector2d>& position, double theta, double dt);
00271   
00280   void addPoseAndTimeDiff(double x, double y, double theta, double dt);
00281   
00283   
00284 
00287 
00293   void insertPose(int index, const PoseSE2& pose);
00294   
00301   void insertPose(int index, const Eigen::Ref<const Eigen::Vector2d>& position, double theta);
00302   
00310   void insertPose(int index, double x, double y, double theta);
00311   
00317   void insertTimeDiff(int index, double dt);
00318     
00323   void deletePose(int index);
00324   
00330   void deletePoses(int index, int number);
00331 
00336   void deleteTimeDiff(int index);
00337         
00343   void deleteTimeDiffs(int index, int number);
00344   
00346   
00347   
00350   
00369   bool initTEBtoGoal(const PoseSE2& start, const PoseSE2& goal, double diststep=0, double timestep=1, int min_samples = 3, bool guess_backwards_motion = false);
00370   
00371   
00406   template<typename BidirIter, typename Fun>
00407   bool initTEBtoGoal(BidirIter path_start, BidirIter path_end, Fun fun_position, double max_vel_x, double max_vel_theta,
00408                       boost::optional<double> max_acc_x, boost::optional<double> max_acc_theta,
00409                       boost::optional<double> start_orientation, boost::optional<double> goal_orientation, int min_samples = 3, bool guess_backwards_motion = false);  
00410   
00426   bool initTEBtoGoal(const std::vector<geometry_msgs::PoseStamped>& plan, double dt, bool estimate_orient=false, int min_samples = 3, bool guess_backwards_motion = false);
00427   
00429   
00432   
00433   
00449   void updateAndPruneTEB(boost::optional<const PoseSE2&> new_start, boost::optional<const PoseSE2&> new_goal, int min_samples = 3);
00450   
00451   
00479   void autoResize(double dt_ref, double dt_hysteresis, int min_samples = 3, int max_samples=1000);
00480   
00481   
00487   void setPoseVertexFixed(int index, bool status);
00488   
00494   void setTimeDiffVertexFixed(int index, bool status);
00495   
00500   void clearTimedElasticBand();
00501   
00503   
00504   
00507   
00522   int findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_point, double* distance = NULL, int begin_idx=0) const;
00523 
00538   int findClosestTrajectoryPose(const Eigen::Ref<const Eigen::Vector2d>& ref_line_start, const Eigen::Ref<const Eigen::Vector2d>& ref_line_end, double* distance = NULL) const;
00539 
00553   int findClosestTrajectoryPose(const Point2dContainer& vertices, double* distance = NULL) const;
00554 
00566   int findClosestTrajectoryPose(const Obstacle& obstacle, double* distance = NULL) const;
00567   
00568   
00572   int sizePoses() const {return (int)pose_vec_.size();};
00573   
00577   int sizeTimeDiffs() const {return (int)timediff_vec_.size();};
00578   
00582   bool isInit() const {return !timediff_vec_.empty() && !pose_vec_.empty();}
00583 
00587   double getSumOfAllTimeDiffs() const;
00588   
00592   double getAccumulatedDistance() const;
00593   
00608   bool detectDetoursBackwards(double threshold=0) const;
00609   
00620   bool isTrajectoryInsideRegion(double radius, double max_dist_behind_robot=-1, int skip_poses=0);
00621   
00622   
00623   
00625         
00626 protected:
00627   PoseSequence pose_vec_; 
00628   TimeDiffSequence timediff_vec_;  
00629   
00630 public:
00631   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00632 };
00633 
00634 } // namespace teb_local_planner
00635 
00636 
00637 // include template implementations / definitions
00638 #include <teb_local_planner/timed_elastic_band.hpp>
00639 
00640 
00641 #endif /* TIMED_ELASTIC_BAND_H_ */


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sat Jun 8 2019 20:21:34