Class PRM
Defined in File PRM.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Derived Type
public ompl::geometric::PRMstar
(Class PRMstar)
Class Documentation
-
class PRM : public ompl::base::Planner
Probabilistic RoadMap planner.
- Short description
PRM is a planner that constructs a roadmap of milestones that approximate the connectivity of the state space. The milestones are valid states in the state space. Near-by milestones are connected by valid motions. Finding a motion plan that connects two given states is reduced to a discrete search (this implementation uses A*) in the roadmap.
- 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[PDF] [more]
Subclassed by ompl::geometric::PRMstar
Public Types
-
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.
- Any BGL graph representation could be used here. Because we
expect the roadmap to be sparse (m<n^2), an adjacency_list is more appropriate than an adjacency_matrix.
- Obviously, a ompl::base::State* vertex property is required.
The incremental connected components algorithm requires vertex_predecessor_t and vertex_rank_t properties. If boost::vecS is not used for vertex storage, then there must also be a boost:vertex_index_t property manually added.
- Edges should be undirected and have a weight property.
-
using RoadmapNeighbors = std::shared_ptr<NearestNeighbors<Vertex>>
A nearest neighbors data structure for roadmap vertices.
Public Functions
-
PRM(const base::SpaceInformationPtr &si, bool starStrategy = false)
Constructor.
-
PRM(const base::PlannerData &data, bool starStrategy = false)
Constructor.
-
~PRM() override
-
void setProblemDefinition(const base::ProblemDefinitionPtr &pdef) override
-
inline 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.
- The behavior and performance of PRM can be changed drastically
by varying the number and properties if the milestones that are connected to each other.
- Parameters:
pdef – A function that takes a milestone as an argument and returns a collection of other milestones to which a connection attempt must be made. The default connection strategy is to connect a milestone’s 10 closest neighbors.
-
void setDefaultConnectionStrategy()
Set default strategy for connecting to nearest neighbors
-
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
This only returns a meaningful answer if the connection strategy is of type KStrategy.
-
inline void setConnectionFilter(const ConnectionFilter &connectionFilter)
Set the function that can reject a milestone connection.
- The given function is called immediately before a connection
is checked for collision and added to the roadmap. Other neighbors may have already been connected before this function is called. This allows certain heuristics that use the structure of the roadmap (like connected components or useful cycles) to be implemented by changing this function.
- Parameters:
connectionFilter – A function that takes the new milestone, a neighboring milestone and returns whether a connection should be attempted.
-
virtual 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.
-
virtual 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.
-
virtual 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.
-
virtual 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>
inline void setNearestNeighbors() Set a different nearest neighbors datastructure.
-
virtual 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.
-
inline unsigned long int milestoneCount() const
Return the number of milestones currently in the graph.
-
inline unsigned long int edgeCount() const
Return the number of edges currently in the graph.
-
inline const RoadmapNeighbors &getNearestNeighbors()
Protected Functions
-
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)
Thread that checks for 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.
-
inline double distanceFunction(const Vertex a, const Vertex b) const
Compute distance between two milestones (this is simply distance between the states of the milestones)
-
inline std::string getIterationCount() const
-
inline std::string getBestCost() const
-
inline std::string getMilestoneCountString() const
-
inline std::string getEdgeCountString() const
Protected Attributes
-
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.
-
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)
-
mutable 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.