graph_search.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017,
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  * Authors: Christoph Rösmann, Franz Albers
37  *********************************************************************/
38 
39 #ifndef GRAPH_SEARCH_INTERFACE_H
40 #define GRAPH_SEARCH_INTERFACE_H
41 
42 #ifdef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS
43  #include <boost/graph/adjacency_list.hpp>
44 #else
45  // Workaround for a bug in boost graph library (concerning directed graphs), boost version 1.48:
46  // boost::add_vertex requires a move constructor/assignment operator in one of the underlying boost objects if C++11 is activated,
47  // but they are missing. The compiler fails due to an implicit deletion. We just deactivate C++11 default functions for now.
48  #define BOOST_NO_CXX11_DEFAULTED_FUNCTIONS
49  #include <boost/graph/adjacency_list.hpp>
50  #undef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS
51 #endif
52 
53 #include <boost/graph/graph_traits.hpp>
54 #include <boost/graph/depth_first_search.hpp>
55 #include <boost/utility.hpp>
56 #include <boost/random.hpp>
57 
58 #include <Eigen/Core>
59 
60 #include <geometry_msgs/Twist.h>
61 
65 
66 namespace teb_local_planner
67 {
68 
69 class HomotopyClassPlanner; // Forward declaration
70 
73 {
74 public:
75  Eigen::Vector2d pos; // position of vertices in the map
76  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
77 };
78 
80 typedef boost::adjacency_list < boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property > HcGraph;
82 typedef boost::graph_traits<HcGraph>::vertex_descriptor HcGraphVertexType;
84 typedef boost::graph_traits<HcGraph>::edge_descriptor HcGraphEdgeType;
86 typedef boost::graph_traits<HcGraph>::vertex_iterator HcGraphVertexIterator;
88 typedef boost::graph_traits<HcGraph>::edge_iterator HcGraphEdgeIterator;
90 typedef boost::graph_traits<HcGraph>::adjacency_iterator HcGraphAdjecencyIterator;
91 
93 inline std::complex<long double> getCplxFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph& graph)
94 {
95  return std::complex<long double>(graph[vert_descriptor].pos.x(), graph[vert_descriptor].pos.y());
96 }
97 
99 inline const Eigen::Vector2d& getVector2dFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph& graph)
100 {
101  return graph[vert_descriptor].pos;
102 }
103 
108 {
109 public:
110 
111  virtual void createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false) = 0;
112 
116  void clearGraph() {graph_.clear();}
117 
118  // HcGraph graph() const {return graph_;}
119  // Workaround. graph_ is public for now, beacuse otherwise the compilation fails with the same boost bug mentioned above.
121 
122 protected:
126  GraphSearchInterface(const TebConfig& cfg, HomotopyClassPlanner* hcp) : cfg_(&cfg), hcp_(hcp){}
127 
141  void DepthFirst(HcGraph& g, std::vector<HcGraphVertexType>& visited, const HcGraphVertexType& goal, double start_orientation, double goal_orientation, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false);
142 
143 
144 protected:
145  const TebConfig* cfg_;
147 
148 public:
149  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
150 };
151 
152 
153 
155 {
156 public:
158 
159  virtual ~lrKeyPointGraph(){}
160 
177  virtual void createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false);
178 };
179 
180 
181 
182 
184 {
185 public:
187 
188  virtual ~ProbRoadmapGraph(){}
189 
190 
208  virtual void createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist* start_velocity, bool free_goal_vel = false);
209 
210 private:
211  boost::random::mt19937 rnd_generator_;
212 };
213 } // end namespace
214 
215 #endif // GRAPH_SEARCH_INTERFACE_H
teb_local_planner::ProbRoadmapGraph::rnd_generator_
boost::random::mt19937 rnd_generator_
Random number generator used by createProbRoadmapGraph to sample graph keypoints.
Definition: graph_search.h:211
teb_local_planner::getVector2dFromHcGraph
const Eigen::Vector2d & getVector2dFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph &graph)
Definition: graph_search.h:99
teb_local_planner::GraphSearchInterface::hcp_
HomotopyClassPlanner *const hcp_
Raw pointer to the HomotopyClassPlanner. The HomotopyClassPlanner itself is guaranteed to outlive the...
Definition: graph_search.h:146
cmd_vel_to_ackermann_drive.Twist
Twist
Definition: cmd_vel_to_ackermann_drive.py:56
teb_local_planner::HcGraphVertexIterator
boost::graph_traits< HcGraph >::vertex_iterator HcGraphVertexIterator
Abbrev. for the vertices iterator of the homotopy class search-graph.
Definition: graph_search.h:86
teb_local_planner::GraphSearchInterface::GraphSearchInterface
GraphSearchInterface(const TebConfig &cfg, HomotopyClassPlanner *hcp)
Protected constructor that should be called by subclasses.
Definition: graph_search.h:126
teb_local_planner::HcGraphVertex
Vertex in the graph that is used to find homotopy classes (only stores 2D positions)
Definition: graph_search.h:72
equivalence_relations.h
teb_local_planner::HcGraphVertexType
boost::graph_traits< HcGraph >::vertex_descriptor HcGraphVertexType
Abbrev. for vertex type descriptors in the homotopy class search-graph.
Definition: graph_search.h:82
teb_local_planner::GraphSearchInterface::DepthFirst
void DepthFirst(HcGraph &g, std::vector< HcGraphVertexType > &visited, const HcGraphVertexType &goal, double start_orientation, double goal_orientation, const geometry_msgs::Twist *start_velocity, bool free_goal_vel=false)
Depth First Search implementation to find all paths between the start and the specified goal vertex.
Definition: graph_search.cpp:81
teb_local_planner::lrKeyPointGraph::createGraph
virtual void createGraph(const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist *start_velocity, bool free_goal_vel=false)
Create a graph containing points in the global frame that can be used to explore new possible paths b...
Definition: graph_search.cpp:129
teb_local_planner::lrKeyPointGraph::lrKeyPointGraph
lrKeyPointGraph(const TebConfig &cfg, HomotopyClassPlanner *hcp)
Definition: graph_search.h:157
teb_local_planner::HcGraphEdgeIterator
boost::graph_traits< HcGraph >::edge_iterator HcGraphEdgeIterator
Abbrev. for the edges iterator of the homotopy class search-graph.
Definition: graph_search.h:88
teb_local_planner::ProbRoadmapGraph::~ProbRoadmapGraph
virtual ~ProbRoadmapGraph()
Definition: graph_search.h:188
teb_local_planner::HcGraphAdjecencyIterator
boost::graph_traits< HcGraph >::adjacency_iterator HcGraphAdjecencyIterator
Abbrev. for the adjacency iterator that iterates vertices that are adjecent to the specified one.
Definition: graph_search.h:90
teb_config.h
teb_local_planner::GraphSearchInterface::clearGraph
void clearGraph()
Clear any existing graph of the homotopy class search.
Definition: graph_search.h:116
teb_local_planner::ProbRoadmapGraph::createGraph
virtual void createGraph(const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist *start_velocity, bool free_goal_vel=false)
Create a graph and sample points in the global frame that can be used to explore new possible paths b...
Definition: graph_search.cpp:256
teb_local_planner::lrKeyPointGraph::~lrKeyPointGraph
virtual ~lrKeyPointGraph()
Definition: graph_search.h:159
teb_local_planner::GraphSearchInterface::cfg_
const TebConfig * cfg_
Config class that stores and manages all related parameters.
Definition: graph_search.h:145
start
ROSCPP_DECL void start()
teb_local_planner::TebConfig
Config class for the teb_local_planner and its components.
Definition: teb_config.h:62
teb_local_planner::HomotopyClassPlanner
Local planner that explores alternative homotopy classes, create a plan for each alternative and fina...
Definition: homotopy_class_planner.h:144
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::HcGraph
boost::adjacency_list< boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property > HcGraph
Abbrev. for the homotopy class search-graph type.
Definition: graph_search.h:80
teb_local_planner::HcGraphEdgeType
boost::graph_traits< HcGraph >::edge_descriptor HcGraphEdgeType
Abbrev. for edge type descriptors in the homotopy class search-graph.
Definition: graph_search.h:84
pose_se2.h
teb_local_planner::ProbRoadmapGraph::ProbRoadmapGraph
ProbRoadmapGraph(const TebConfig &cfg, HomotopyClassPlanner *hcp)
Definition: graph_search.h:186
teb_local_planner::HcGraphVertex::pos
Eigen::Vector2d pos
Definition: graph_search.h:75
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::lrKeyPointGraph
Definition: graph_search.h:154
teb_local_planner::GraphSearchInterface
Base class for graph based path planning / homotopy class sampling.
Definition: graph_search.h:107
teb_local_planner::ProbRoadmapGraph
Definition: graph_search.h:183
teb_local_planner::GraphSearchInterface::createGraph
virtual void createGraph(const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist *start_velocity, bool free_goal_vel=false)=0
teb_local_planner::GraphSearchInterface::graph_
HcGraph graph_
Store the graph that is utilized to find alternative homotopy classes.
Definition: graph_search.h:120


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