Base class for graph based path planning / homotopy class sampling. More...
#include <graph_search.h>
Public Member Functions | |
void | clearGraph () |
Clear any existing graph of the homotopy class search. More... | |
virtual void | createGraph (const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist *start_velocity)=0 |
Public Attributes | |
HcGraph | graph_ |
Store the graph that is utilized to find alternative homotopy classes. More... | |
Protected Member Functions | |
void | DepthFirst (HcGraph &g, std::vector< HcGraphVertexType > &visited, const HcGraphVertexType &goal, double start_orientation, double goal_orientation, const geometry_msgs::Twist *start_velocity) |
Depth First Search implementation to find all paths between the start and the specified goal vertex. More... | |
GraphSearchInterface (const TebConfig &cfg, HomotopyClassPlanner *hcp) | |
Protected constructor that should be called by subclasses. More... | |
Protected Attributes | |
const TebConfig * | cfg_ |
Config class that stores and manages all related parameters. More... | |
HomotopyClassPlanner *const | hcp_ |
Raw pointer to the HomotopyClassPlanner. The HomotopyClassPlanner itself is guaranteed to outlive the graph search class it is holding. More... | |
Base class for graph based path planning / homotopy class sampling.
Definition at line 107 of file graph_search.h.
|
inlineprotected |
Protected constructor that should be called by subclasses.
Definition at line 126 of file graph_search.h.
|
inline |
Clear any existing graph of the homotopy class search.
Definition at line 116 of file graph_search.h.
|
pure virtual |
Implemented in teb_local_planner::ProbRoadmapGraph, and teb_local_planner::lrKeyPointGraph.
|
protected |
Depth First Search implementation to find all paths between the start and the specified goal vertex.
Complete paths are stored to the internal path container.
g | Graph on which the depth first should be performed |
visited | A container that stores visited vertices (pass an empty container, it will be filled inside during recursion). |
goal | Desired goal vertex |
start_orientation | Orientation of the first trajectory pose, required to initialize the trajectory/TEB |
goal_orientation | Orientation of the goal trajectory pose, required to initialize the trajectory/TEB |
start_velocity | start velocity (optional) |
Examine adjacent nodes
Recursion for all adjacent vertices
Definition at line 45 of file graph_search.cpp.
|
protected |
Config class that stores and manages all related parameters.
Definition at line 144 of file graph_search.h.
HcGraph teb_local_planner::GraphSearchInterface::graph_ |
Store the graph that is utilized to find alternative homotopy classes.
Definition at line 120 of file graph_search.h.
|
protected |
Raw pointer to the HomotopyClassPlanner. The HomotopyClassPlanner itself is guaranteed to outlive the graph search class it is holding.
Definition at line 145 of file graph_search.h.