Public Member Functions | List of all members
teb_local_planner::lrKeyPointGraph Class Reference

#include <graph_search.h>

Inheritance diagram for teb_local_planner::lrKeyPointGraph:
Inheritance graph
[legend]

Public Member Functions

virtual void createGraph (const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, double obstacle_heading_threshold, const geometry_msgs::Twist *start_velocity)
 Create a graph containing points in the global frame that can be used to explore new possible paths between start and goal. More...
 
 lrKeyPointGraph (const TebConfig &cfg, HomotopyClassPlanner *hcp)
 
virtual ~lrKeyPointGraph ()
 
- Public Member Functions inherited from teb_local_planner::GraphSearchInterface
void clearGraph ()
 Clear any existing graph of the homotopy class search. More...
 

Additional Inherited Members

- Public Attributes inherited from teb_local_planner::GraphSearchInterface
HcGraph graph_
 Store the graph that is utilized to find alternative homotopy classes. More...
 
- Protected Member Functions inherited from teb_local_planner::GraphSearchInterface
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 inherited from teb_local_planner::GraphSearchInterface
const TebConfigcfg_
 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...
 

Detailed Description

Definition at line 153 of file graph_search.h.

Constructor & Destructor Documentation

teb_local_planner::lrKeyPointGraph::lrKeyPointGraph ( const TebConfig cfg,
HomotopyClassPlanner hcp 
)
inline

Definition at line 156 of file graph_search.h.

virtual teb_local_planner::lrKeyPointGraph::~lrKeyPointGraph ( )
inlinevirtual

Definition at line 158 of file graph_search.h.

Member Function Documentation

void teb_local_planner::lrKeyPointGraph::createGraph ( const PoseSE2 start,
const PoseSE2 goal,
double  dist_to_obst,
double  obstacle_heading_threshold,
const geometry_msgs::Twist *  start_velocity 
)
virtual

Create a graph containing points in the global frame that can be used to explore new possible paths between start and goal.

This version of the graph creation places a keypoint on the left and right side of each obstacle w.r.t to the goal heading.
All feasible paths between start and goal point are extracted using a Depth First Search afterwards.
This version works very well for small point obstacles. For more complex obstacles call the createProbRoadmapGraph() method that samples keypoints in a predefined area and hopefully finds all relevant alternative paths.

See also
createProbRoadmapGraph
Parameters
startStart pose from wich to start on (e.g. the current robot pose).
goalGoal pose to find paths to (e.g. the robot's goal).
dist_to_obstAllowed distance to obstacles: if not satisfying, the path will be rejected (note, this is not the distance used for optimization).
obstacle_heading_thresholdValue of the normalized scalar product between obstacle heading and goal heading in order to take them (obstacles) into account [0,1]
start_velocitystart velocity (optional)

Implements teb_local_planner::GraphSearchInterface.

Definition at line 93 of file graph_search.cpp.


The documentation for this class was generated from the following files:


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08