39 #ifndef GRAPH_SEARCH_INTERFACE_H 40 #define GRAPH_SEARCH_INTERFACE_H 42 #ifdef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS 43 #include <boost/graph/adjacency_list.hpp> 48 #define BOOST_NO_CXX11_DEFAULTED_FUNCTIONS 49 #include <boost/graph/adjacency_list.hpp> 50 #undef BOOST_NO_CXX11_DEFAULTED_FUNCTIONS 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> 60 #include <geometry_msgs/Twist.h> 69 class HomotopyClassPlanner;
76 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
80 typedef boost::adjacency_list < boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property >
HcGraph;
93 inline std::complex<long double>
getCplxFromHcGraph(HcGraphVertexType vert_descriptor,
const HcGraph& graph)
95 return std::complex<long double>(graph[vert_descriptor].pos.x(), graph[vert_descriptor].pos.y());
101 return graph[vert_descriptor].pos;
111 virtual void createGraph(
const PoseSE2& start,
const PoseSE2& goal,
double dist_to_obst,
double obstacle_heading_threshold,
const geometry_msgs::Twist* start_velocity) = 0;
140 void DepthFirst(HcGraph& g, std::vector<HcGraphVertexType>& visited,
const HcGraphVertexType& goal,
double start_orientation,
double goal_orientation,
const geometry_msgs::Twist* start_velocity);
148 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
175 virtual void createGraph(
const PoseSE2& start,
const PoseSE2& goal,
double dist_to_obst,
double obstacle_heading_threshold,
const geometry_msgs::Twist* start_velocity);
205 virtual void createGraph(
const PoseSE2& start,
const PoseSE2& goal,
double dist_to_obst,
double obstacle_heading_threshold,
const geometry_msgs::Twist* start_velocity);
212 #endif // GRAPH_SEARCH_INTERFACE_H boost::graph_traits< HcGraph >::vertex_descriptor HcGraphVertexType
Abbrev. for vertex type descriptors in the homotopy class search-graph.
const TebConfig * cfg_
Config class that stores and manages all related parameters.
Config class for the teb_local_planner and its components.
HcGraph graph_
Store the graph that is utilized to find alternative homotopy classes.
virtual ~ProbRoadmapGraph()
std::complex< long double > getCplxFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph &graph)
Inline function used for initializing the TEB in combination with HCP graph vertex descriptors...
Local planner that explores alternative homotopy classes, create a plan for each alternative and fina...
boost::graph_traits< HcGraph >::vertex_iterator HcGraphVertexIterator
Abbrev. for the vertices iterator of the homotopy class search-graph.
void clearGraph()
Clear any existing graph of the homotopy class search.
Base class for graph based path planning / homotopy class sampling.
HomotopyClassPlanner *const hcp_
Raw pointer to the HomotopyClassPlanner. The HomotopyClassPlanner itself is guaranteed to outlive the...
virtual ~lrKeyPointGraph()
boost::graph_traits< HcGraph >::edge_iterator HcGraphEdgeIterator
Abbrev. for the edges iterator of the homotopy class search-graph.
GraphSearchInterface(const TebConfig &cfg, HomotopyClassPlanner *hcp)
Protected constructor that should be called by subclasses.
boost::random::mt19937 rnd_generator_
Random number generator used by createProbRoadmapGraph to sample graph keypoints. ...
Vertex in the graph that is used to find homotopy classes (only stores 2D positions) ...
boost::graph_traits< HcGraph >::adjacency_iterator HcGraphAdjecencyIterator
Abbrev. for the adjacency iterator that iterates vertices that are adjecent to the specified one...
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
boost::graph_traits< HcGraph >::edge_descriptor HcGraphEdgeType
Abbrev. for edge type descriptors in the homotopy class search-graph.
ProbRoadmapGraph(const TebConfig &cfg, HomotopyClassPlanner *hcp)
lrKeyPointGraph(const TebConfig &cfg, HomotopyClassPlanner *hcp)
const Eigen::Vector2d & getVector2dFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph &graph)
boost::adjacency_list< boost::listS, boost::vecS, boost::directedS, HcGraphVertex, boost::no_property > HcGraph
Abbrev. for the homotopy class search-graph type.