ompl::geometric::PRMstar Class Reference
PRM* planner. More...
#include <ompl/geometric/planners/prm/PRMstar.h>
Inheritance diagram for ompl::geometric::PRMstar:
Public Member Functions | |
PRMstar (const base::SpaceInformationPtr &si) | |
Constructor. | |
PRMstar (const base::PlannerData &data) | |
Constructor. | |
Public Member Functions inherited from ompl::geometric::PRM | |
PRM (const base::SpaceInformationPtr &si, bool starStrategy=false) | |
Constructor. | |
PRM (const base::PlannerData &data, bool starStrategy=false) | |
Constructor. | |
void | setProblemDefinition (const base::ProblemDefinitionPtr &pdef) override |
void | setConnectionStrategy (const ConnectionStrategy &connectionStrategy) |
Set the connection strategy function that specifies the milestones that connection attempts will be make to for a given milestone. More... | |
void | setDefaultConnectionStrategy () |
void | setMaxNearestNeighbors (unsigned int k) |
Convenience function that sets the connection strategy to the default one with k nearest neighbors. | |
unsigned int | getMaxNearestNeighbors () const |
return the maximum number of nearest neighbors to connect a sample to More... | |
void | setConnectionFilter (const ConnectionFilter &connectionFilter) |
Set the function that can reject a milestone connection. More... | |
void | getPlannerData (base::PlannerData &data) const override |
Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between). | |
void | constructRoadmap (const base::PlannerTerminationCondition &ptc) |
While the termination condition allows, this function will construct the roadmap (using growRoadmap() and expandRoadmap(), maintaining a 2:1 ratio for growing/expansion of roadmap) | |
void | growRoadmap (double growTime) |
If the user desires, the roadmap can be improved for the given time (seconds). The solve() method will also improve the roadmap, as needed. | |
void | growRoadmap (const base::PlannerTerminationCondition &ptc) |
If the user desires, the roadmap can be improved until a given condition is true. The solve() method will also improve the roadmap, as needed. | |
void | expandRoadmap (double expandTime) |
Attempt to connect disjoint components in the roadmap using random bouncing motions (the PRM expansion step) for the given time (seconds). | |
void | expandRoadmap (const base::PlannerTerminationCondition &ptc) |
Attempt to connect disjoint components in the roadmap using random bouncing motions (the PRM expansion step) until the given condition evaluates true. | |
base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) override |
Function that can solve the motion planning problem. Grows a roadmap using constructRoadmap(). This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work for more time on an unsolved problem, for example. Start and goal states from the currently specified ProblemDefinition are cached. This means that between calls to solve(), input states are only added, not removed. When using PRM as a multi-query planner, the input states should be however cleared, without clearing the roadmap itself. This can be done using the clearQuery() function. | |
void | clearQuery () override |
Clear the query previously loaded from the ProblemDefinition. Subsequent calls to solve() will reuse the previously computed roadmap, but will clear the set of input states constructed by the previous call to solve(). This enables multi-query functionality for PRM. | |
void | clear () override |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
Set a different nearest neighbors datastructure. | |
void | setup () override |
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving. | |
const Graph & | getRoadmap () const |
unsigned long int | milestoneCount () const |
Return the number of milestones currently in the graph. | |
unsigned long int | edgeCount () const |
Return the number of edges currently in the graph. | |
const RoadmapNeighbors & | getNearestNeighbors () |
Public Member Functions inherited from ompl::base::Planner | |
Planner (const Planner &)=delete | |
Planner & | operator= (const Planner &)=delete |
Planner (SpaceInformationPtr si, std::string name) | |
Constructor. | |
virtual | ~Planner ()=default |
Destructor. | |
template<class T > | |
T * | as () |
Cast this instance to a desired type. More... | |
template<class T > | |
const T * | as () const |
Cast this instance to a desired type. More... | |
const SpaceInformationPtr & | getSpaceInformation () const |
Get the space information this planner is using. | |
const ProblemDefinitionPtr & | getProblemDefinition () const |
Get the problem definition the planner is trying to solve. | |
ProblemDefinitionPtr & | getProblemDefinition () |
Get the problem definition the planner is trying to solve. | |
const PlannerInputStates & | getPlannerInputStates () const |
Get the planner input states. | |
virtual void | setProblemDefinition (const ProblemDefinitionPtr &pdef) |
Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear() or clearQuery(). | |
PlannerStatus | solve (const PlannerTerminationConditionFn &ptc, double checkInterval) |
Same as above except the termination condition is only evaluated at a specified interval. | |
PlannerStatus | solve (double solveTime) |
Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning. | |
const std::string & | getName () const |
Get the name of the planner. | |
void | setName (const std::string &name) |
Set the name of the planner. | |
const PlannerSpecs & | getSpecs () const |
Return the specifications (capabilities of this planner) | |
virtual void | checkValidity () |
Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception. | |
bool | isSetup () const |
Check if setup() was called for this planner. | |
ParamSet & | params () |
Get the parameters for this planner. | |
const ParamSet & | params () const |
Get the parameters for this planner. | |
const PlannerProgressProperties & | getPlannerProgressProperties () const |
Retrieve a planner's planner progress property map. | |
virtual void | printProperties (std::ostream &out) const |
Print properties of the motion planner. | |
virtual void | printSettings (std::ostream &out) const |
Print information about the motion planner's settings. | |
Additional Inherited Members | |
Public Types inherited from ompl::geometric::PRM | |
using | Graph = boost::adjacency_list< boost::vecS, boost::vecS, boost::undirectedS, boost::property< vertex_state_t, base::State *, boost::property< vertex_total_connection_attempts_t, unsigned long int, boost::property< vertex_successful_connection_attempts_t, unsigned long int, boost::property< boost::vertex_predecessor_t, unsigned long int, boost::property< boost::vertex_rank_t, unsigned long int > >> >>, boost::property< boost::edge_weight_t, base::Cost > > |
The underlying roadmap graph. More... | |
using | Vertex = boost::graph_traits< Graph >::vertex_descriptor |
The type for a vertex in the roadmap. | |
using | Edge = boost::graph_traits< Graph >::edge_descriptor |
The type for an edge in the roadmap. | |
using | RoadmapNeighbors = std::shared_ptr< NearestNeighbors< Vertex > > |
A nearest neighbors data structure for roadmap vertices. | |
using | ConnectionStrategy = std::function< const std::vector< Vertex > &(const Vertex)> |
A function returning the milestones that should be attempted to connect to. | |
using | ConnectionFilter = std::function< bool(const Vertex &, const Vertex &)> |
A function that can reject connections. More... | |
Public Types inherited from ompl::base::Planner | |
using | PlannerProgressProperty = std::function< std::string()> |
Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine. | |
using | PlannerProgressProperties = std::map< std::string, PlannerProgressProperty > |
A dictionary which maps the name of a progress property to the function to be used for querying that property. | |
Protected Member Functions inherited from ompl::geometric::PRM | |
void | freeMemory () |
Free all the memory allocated by the planner. | |
Vertex | addMilestone (base::State *state) |
Construct a milestone for a given state (state), store it in the nearest neighbors data structure and then connect it to the roadmap in accordance to the connection strategy. | |
void | uniteComponents (Vertex m1, Vertex m2) |
Make two milestones (m1 and m2) be part of the same connected component. The component with fewer elements will get the id of the component with more elements. | |
bool | sameComponent (Vertex m1, Vertex m2) |
Check if two milestones (m1 and m2) are part of the same connected component. This is not a const function since we use incremental connected components from boost. | |
void | growRoadmap (const base::PlannerTerminationCondition &ptc, base::State *workState) |
Randomly sample the state space, add and connect milestones in the roadmap. Stop this process when the termination condition ptc returns true. Use workState as temporary memory. | |
void | expandRoadmap (const base::PlannerTerminationCondition &ptc, std::vector< base::State * > &workStates) |
Attempt to connect disjoint components in the roadmap using random bounding motions (the PRM expansion step) | |
void | checkForSolution (const base::PlannerTerminationCondition &ptc, base::PathPtr &solution) |
bool | maybeConstructSolution (const std::vector< Vertex > &starts, const std::vector< Vertex > &goals, base::PathPtr &solution) |
Check if there exists a solution, i.e., there exists a pair of milestones such that the first is in start and the second is in goal, and the two milestones are in the same connected component. If a solution is found, it is constructed in the solution argument. | |
ompl::base::Cost | constructApproximateSolution (const std::vector< Vertex > &starts, const std::vector< Vertex > &goals, base::PathPtr &solution) |
(Assuming that there is always an approximate solution), finds an approximate solution. | |
bool | addedNewSolution () const |
Returns the value of the addedNewSolution_ member. | |
base::PathPtr | constructSolution (const Vertex &start, const Vertex &goal) |
Given two milestones from the same connected component, construct a path connecting them and set it as the solution. | |
base::Cost | costHeuristic (Vertex u, Vertex v) const |
Given two vertices, returns a heuristic on the cost of the path connecting them. This method wraps OptimizationObjective::motionCostHeuristic. | |
double | distanceFunction (const Vertex a, const Vertex b) const |
Compute distance between two milestones (this is simply distance between the states of the milestones) | |
std::string | getIterationCount () const |
std::string | getBestCost () const |
std::string | getMilestoneCountString () const |
std::string | getEdgeCountString () const |
Protected Member Functions inherited from ompl::base::Planner | |
template<typename T , typename PlannerType , typename SetterType , typename GetterType > | |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter, const std::string &rangeSuggestion="") |
This function declares a parameter for this planner instance, and specifies the setter and getter functions. | |
template<typename T , typename PlannerType , typename SetterType > | |
void | declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const std::string &rangeSuggestion="") |
This function declares a parameter for this planner instance, and specifies the setter function. | |
void | addPlannerProgressProperty (const std::string &progressPropertyName, const PlannerProgressProperty &prop) |
Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map. | |
Protected Attributes inherited from ompl::geometric::PRM | |
bool | starStrategy_ |
Flag indicating whether the default connection strategy is the Star strategy. | |
base::ValidStateSamplerPtr | sampler_ |
Sampler user for generating valid samples in the state space. | |
base::StateSamplerPtr | simpleSampler_ |
Sampler user for generating random in the state space. | |
RoadmapNeighbors | nn_ |
Nearest neighbors data structure. | |
Graph | g_ |
Connectivity graph. | |
std::vector< Vertex > | startM_ |
Array of start milestones. | |
std::vector< Vertex > | goalM_ |
Array of goal milestones. | |
boost::property_map< Graph, vertex_state_t >::type | stateProperty_ |
Access to the internal base::state at each Vertex. | |
boost::property_map< Graph, vertex_total_connection_attempts_t >::type | totalConnectionAttemptsProperty_ |
Access to the number of total connection attempts for a vertex. | |
boost::property_map< Graph, vertex_successful_connection_attempts_t >::type | successfulConnectionAttemptsProperty_ |
Access to the number of successful connection attempts for a vertex. | |
boost::property_map< Graph, boost::edge_weight_t >::type | weightProperty_ |
Access to the weights of each Edge. | |
boost::disjoint_sets< boost::property_map< Graph, boost::vertex_rank_t >::type, boost::property_map< Graph, boost::vertex_predecessor_t >::type > | disjointSets_ |
Data structure that maintains the connected components. | |
ConnectionStrategy | connectionStrategy_ |
Function that returns the milestones to attempt connections with. | |
ConnectionFilter | connectionFilter_ |
Function that can reject a milestone connection. | |
bool | userSetConnectionStrategy_ {false} |
Flag indicating whether the employed connection strategy was set by the user (or defaults are assumed) | |
RNG | rng_ |
Random number generator. | |
bool | addedNewSolution_ {false} |
A flag indicating that a solution has been added during solve() | |
std::mutex | graphMutex_ |
Mutex to guard access to the Graph member (g_) | |
base::OptimizationObjectivePtr | opt_ |
Objective cost function for PRM graph edges. | |
unsigned long int | iterations_ {0} |
Number of iterations the algorithm performed. | |
base::Cost | bestCost_ {std::numeric_limits<double>::quiet_NaN()} |
Best cost found so far by algorithm. | |
Protected Attributes inherited from ompl::base::Planner | |
SpaceInformationPtr | si_ |
The space information for which planning is done. | |
ProblemDefinitionPtr | pdef_ |
The user set problem definition. | |
PlannerInputStates | pis_ |
Utility class to extract valid input states | |
std::string | name_ |
The name of this planner. | |
PlannerSpecs | specs_ |
The specifications of the planner (its capabilities) | |
ParamSet | params_ |
A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function. | |
PlannerProgressProperties | plannerProgressProperties_ |
A mapping between this planner's progress property names and the functions used for querying those progress properties. | |
bool | setup_ |
Flag indicating whether setup() has been called. | |
Detailed Description
PRM* planner.
Run PRM with the "star strategy". Instead of setting the value "k" for how many neighbors to connect, automatically compute it based on the coverage of the space, guaranteeing optimality of solutions.
- Short description
- External documentation
- L.E. Kavraki, P.Švestka, J.-C. Latombe, and M.H. Overmars, Probabilistic roadmaps for path planning in high-dimensional configuration spaces, IEEE Trans. on Robotics and Automation, vol. 12, pp. 566–580, Aug. 1996. DOI: 10.1109/70.508439
S. Karaman and E. Frazzoli, Sampling-based Algorithms for Optimal Motion Planning, International Journal of Robotics Research, vol. 30, no.7, pp. 846-894, 2011. DOI: 10.1177/0278364911406761
The documentation for this class was generated from the following files:
- ompl/geometric/planners/prm/PRMstar.h
- ompl/geometric/planners/prm/src/PRMstar.cpp