#include <graph_search.h>
|
boost::random::mt19937 | rnd_generator_ |
| Random number generator used by createProbRoadmapGraph to sample graph keypoints. More...
|
|
Definition at line 181 of file graph_search.h.
virtual teb_local_planner::ProbRoadmapGraph::~ProbRoadmapGraph |
( |
| ) |
|
|
inlinevirtual |
void teb_local_planner::ProbRoadmapGraph::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 and sample points in the global frame that can be used to explore new possible paths between start and goal.
This version of the graph samples keypoints in a predefined area (config) in the current frame between start and goal.
Afterwards all feasible paths between start and goal point are extracted using a Depth First Search.
Use the sampling method for complex, non-point or huge obstacles.
You may call createGraph() instead.
- See also
- createGraph
- Parameters
-
start | Start pose from wich to start on (e.g. the current robot pose). |
goal | Goal pose to find paths to (e.g. the robot's goal). |
dist_to_obst | Allowed distance to obstacles: if not satisfying, the path will be rejected (note, this is not the distance used for optimization). |
no_samples | number of random samples |
obstacle_heading_threshold | Value of the normalized scalar product between obstacle heading and goal heading in order to take them (obstacles) into account [0,1] |
start_velocity | start velocity (optional) |
Find all paths between start and goal!
Implements teb_local_planner::GraphSearchInterface.
Definition at line 220 of file graph_search.cpp.
boost::random::mt19937 teb_local_planner::ProbRoadmapGraph::rnd_generator_ |
|
private |
Random number generator used by createProbRoadmapGraph to sample graph keypoints.
Definition at line 208 of file graph_search.h.
The documentation for this class was generated from the following files: