homotopy_class_planner.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 HOMOTOPY_CLASS_PLANNER_H_
00040 #define HOMOTOPY_CLASS_PLANNER_H_
00041 
00042 #include <math.h>
00043 #include <algorithm>
00044 #include <functional>
00045 #include <vector>
00046 #include <iterator>
00047 
00048 #ifdef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS
00049   #include <boost/graph/adjacency_list.hpp>
00050 #else
00051   // Workaround for a bug in boost graph library (concerning directed graphs), boost version 1.48:
00052   // boost::add_vertex requires a move constructor/assignment operator in one of the underlying boost objects if C++11 is activated,
00053   // but they are missing. The compiler fails due to an implicit deletion. We just deactivate C++11 default functions for now.
00054   #define BOOST_NO_CXX11_DEFAULTED_FUNCTIONS
00055   #include <boost/graph/adjacency_list.hpp>
00056   #undef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS
00057 #endif
00058 
00059 #include <boost/graph/graph_traits.hpp>
00060 #include <boost/graph/depth_first_search.hpp>
00061 #include <boost/shared_ptr.hpp>
00062 #include <boost/random.hpp>
00063 #include <boost/utility.hpp>
00064 
00065 
00066 #include <visualization_msgs/Marker.h>
00067 #include <geometry_msgs/Point.h>
00068 #include <std_msgs/ColorRGBA.h>
00069 
00070 #include <ros/console.h>
00071 #include <ros/ros.h>
00072 
00073 #include <teb_local_planner/planner_interface.h>
00074 #include <teb_local_planner/teb_config.h>
00075 #include <teb_local_planner/obstacles.h>
00076 #include <teb_local_planner/optimal_planner.h>
00077 #include <teb_local_planner/visualization.h>
00078 #include <teb_local_planner/robot_footprint_model.h>
00079 
00080 
00081 namespace teb_local_planner
00082 {
00083   
00084  
00086 struct HcGraphVertex
00087 { 
00088 public:
00089   Eigen::Vector2d pos; // position of vertices in the map
00090   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00091 };
00092 
00094 typedef boost::adjacency_list < boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property > HcGraph;
00096 typedef boost::graph_traits<HcGraph>::vertex_descriptor HcGraphVertexType;
00098 typedef boost::graph_traits<HcGraph>::edge_descriptor HcGraphEdgeType;
00100 typedef boost::graph_traits<HcGraph>::vertex_iterator HcGraphVertexIterator;
00102 typedef boost::graph_traits<HcGraph>::edge_iterator HcGraphEdgeIterator;
00104 typedef boost::graph_traits<HcGraph>::adjacency_iterator HcGraphAdjecencyIterator;
00105 
00130 class HomotopyClassPlanner : public PlannerInterface
00131 {
00132 public:
00133 
00138   HomotopyClassPlanner();
00139   
00148   HomotopyClassPlanner(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
00149                        TebVisualizationPtr visualization = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
00150     
00154   virtual ~HomotopyClassPlanner();
00155   
00164   void initialize(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
00165                   TebVisualizationPtr visualization = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
00166   
00167   
00168   
00171   
00184   virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
00185   
00197   virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
00198   
00210   virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const Eigen::Vector2d& start_vel, bool free_goal_vel=false);
00211   
00219   virtual bool getVelocityCommand(double& v, double& omega) const;
00220   
00229   TebOptimalPlannerPtr bestTeb() const {return tebs_.empty() ? TebOptimalPlannerPtr() : tebs_.size()==1 ? tebs_.front() : best_teb_;}
00230     
00244   virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
00245                                     double inscribed_radius = 0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1);
00246   
00248   
00251   
00257   void setVisualization(TebVisualizationPtr visualization);
00258   
00265   virtual void visualize();
00266   
00268   
00271     
00272  
00288   void exploreHomotopyClassesAndInitTebs(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, boost::optional<const Eigen::Vector2d&> start_vel);
00289 
00290   
00296   void deleteTebDetours(double threshold=0.0);
00297  
00298   
00312   template<typename BidirIter, typename Fun>
00313   void addAndInitNewTeb(BidirIter path_start, BidirIter path_end, Fun fun_position, double start_orientation, double goal_orientation, boost::optional<const Eigen::Vector2d&> start_velocity); 
00314   
00321   void addAndInitNewTeb(const PoseSE2& start, const PoseSE2& goal, boost::optional<const Eigen::Vector2d&> start_velocity); 
00322   
00328   void addAndInitNewTeb(const std::vector<geometry_msgs::PoseStamped>& initial_plan, boost::optional<const Eigen::Vector2d&> start_velocity);
00329   
00336   void updateAllTEBs(boost::optional<const PoseSE2&> start, boost::optional<const PoseSE2&> goal,  boost::optional<const Eigen::Vector2d&> start_velocity);
00337   
00338   
00346   void optimizeAllTEBs(unsigned int iter_innerloop, unsigned int iter_outerloop);
00347   
00355   TebOptimalPlannerPtr selectBestTeb();
00356   
00358   
00364   void clearPlanner() {graph_.clear(); h_signatures_.clear(); tebs_.clear(); initial_plan_ = NULL;}
00365   
00375   virtual bool isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const;
00376   
00401   template<typename BidirIter, typename Fun>
00402   static std::complex<long double> calculateHSignature(BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer* obstacles = NULL, double prescaler = 1);
00403   
00408   const TebOptPlannerContainer& getTrajectoryContainer() const {return tebs_;};
00409   
00418   virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);  
00419   
00426   inline static bool isHSignatureSimilar(const std::complex<long double>& h1, const std::complex<long double>& h2, double threshold)
00427   {
00428       double diff_real = std::abs(h2.real() - h1.real());
00429       double diff_imag = std::abs(h2.imag() - h1.imag());
00430       if (diff_real<=threshold && diff_imag<=threshold)
00431         return true; // Found! Homotopy class already exists, therefore nothing added  
00432       return false;
00433   }
00434     
00435 protected:
00436   
00439   
00455   void createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, boost::optional<const Eigen::Vector2d&> start_velocity);
00456   
00473   void createProbRoadmapGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, int no_samples, double obstacle_heading_threshold, boost::optional<const Eigen::Vector2d&> start_velocity);
00474   
00480   bool hasHSignature(const std::complex<long double>& H) const;
00481   
00488   bool addHSignatureIfNew(const std::complex<long double>& H, bool lock=false);
00489   
00499   void renewAndAnalyzeOldTebs(bool delete_detours);
00500   
00509   void updateReferenceTrajectoryViaPoints(bool all_trajectories);
00510   
00523   void DepthFirst(HcGraph& g, std::vector<HcGraphVertexType>& visited, const HcGraphVertexType& goal,
00524                   double start_orientation, double goal_orientation, boost::optional<const Eigen::Vector2d&> start_velocity);
00525  
00529   void clearGraph() {graph_.clear();}
00530   
00536   int bestTebIdx() const;
00537   
00539   
00540     
00541   // external objects (store weak pointers)
00542   ObstContainer* obstacles_; 
00543   const ViaPointContainer* via_points_; 
00544   const TebConfig* cfg_; 
00545   
00546   // internal objects (memory management owned)
00547   TebVisualizationPtr visualization_; 
00548   TebOptimalPlannerPtr best_teb_; 
00549   RobotFootprintModelPtr robot_model_; 
00550   
00551   const std::vector<geometry_msgs::PoseStamped>* initial_plan_; 
00552   std::complex<long double> initial_plan_h_sig_; 
00553   
00554   TebOptPlannerContainer tebs_; 
00555   
00556   HcGraph graph_; 
00557  
00558   std::vector< std::pair<std::complex<long double>, bool> > h_signatures_; 
00559                                                                           //   The second parameter denotes whether to exclude the h-signature from detour deletion or not (true: keep).
00560   
00561   boost::random::mt19937 rnd_generator_; 
00562       
00563   bool initialized_; 
00564   
00565   
00566 
00567 public:
00568   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00569     
00570     
00571 };
00572 
00574 typedef boost::shared_ptr<HomotopyClassPlanner> HomotopyClassPlannerPtr;
00575 
00576 
00577 } // namespace teb_local_planner
00578 
00579 // include template implementations / definitions
00580 #include <teb_local_planner/homotopy_class_planner.hpp>
00581 
00582 #endif /* HOMOTOPY_CLASS_PLANNER_H_ */


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:15