ompl::geometric::CForest Class Reference

Coupled Forest of Random Engrafting Search Trees. More...

#include <ompl/geometric/planners/cforest/CForest.h>

Inheritance diagram for ompl::geometric::CForest:

List of all members.

Public Member Functions

 CForest (const base::SpaceInformationPtr &si)
virtual void getPlannerData (base::PlannerData &data) const
 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).
virtual void clear ()
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
template<class T >
void addPlannerInstance ()
 Add an specific planner instance.
template<class T >
void addPlannerInstances (std::size_t num=2)
 Add an specific planner instance.
void clearPlannerInstances ()
 Remove all planner instances.
base::PlannerPtrgetPlannerInstance (const std::size_t idx)
 Return an specific planner instance.
virtual void setup ()
 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.
virtual base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc)
 Function that can solve the motion planning problem. 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. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to ptc returns true.
void addSampler (base::StateSamplerPtr sampler)
void setPrune (const bool prune)
 Option to control whether the tree is pruned during the search.
bool getPrune () const
 Get the state of the pruning option.
void setNumThreads (unsigned int numThreads=0)
 Set default number of threads to use when no planner instances are specified by the user.
unsigned int getNumThreads ()
 Get default number of threads used by CForest when no planner instances are specified by the user.
std::string getBestCost () const
 Get best cost among all the planners.
std::string getNumPathsShared () const
 Get number of paths shared by the algorithm.
std::string getNumStatesShared () const
 Get number of states actually shared by the algorithm.

Protected Member Functions

void solve (base::Planner *planner, const base::PlannerTerminationCondition &ptc)
 Manages the call to solve() for each individual planner.

Protected Attributes

base::OptimizationObjectivePtr opt_
 Optimization objective taken into account when planning.
std::vector< base::PlannerPtrplanners_
 The set of planners to be used.
std::vector
< base::StateSamplerPtr
samplers_
 The set of sampler allocated by the planners.
boost::unordered_set< const
base::State * > 
statesShared_
 Stores the states already shared to check if a specific state has been shared.
base::Cost bestCost_
 Cost of the best path found so far among planners.
unsigned int numPathsShared_
 Number of paths shared among threads.
unsigned int numStatesShared_
 Number of states shared among threads.
boost::mutex newSolutionFoundMutex_
 Mutex to control the access to the newSolutionFound() method.
boost::mutex addSamplerMutex_
 Mutex to control the access to samplers_.
bool prune_
 Flag to control the tree pruning.
unsigned int numThreads_
 Default number of threads to use when no planner instances are specified by the user.

Detailed Description

Coupled Forest of Random Engrafting Search Trees.

Short description
CForest (Coupled Forest of Random Engrafting Search Trees) is a parallelization framework that is designed for single-query shortest path planning algorithms. It is not a planning algorithm per se.

CForest is designed to be used with any random tree algorithm that operates in any configuration space such that: 1) the search tree has almost sure convergence to the optimal solution and 2) the configuration space obeys the triangle inequality. It relies in the OptimizationObjective set for the underlying planners.

See also the extensive documentation [here](CForest.html).

External documentation
M. Otte, N. Correll, C-FOREST: Parallel Shortest Path Planning With Superlinear Speedup, IEEE Transactions on Robotics, Vol 20, No 3, 2013. DOI: [10.1109/TRO.2013.2240176](http://dx.doi.org/10.1109/TRO.2013.2240176)
[[PDF]](http://ieeexplore.ieee.org/ielx5/8860/6522877/06425493.pdf?tp=&amp;arnumber=6425493&amp;isnumber=6522877)

Definition at line 78 of file CForest.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines