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:
Public Member Functions | |
CForest (const base::SpaceInformationPtr &si) | |
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 | clear () override |
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 specific planner instances. CFOREST sets the planner's parameter named focus_search (if present) to the current value of CFOREST's focus_search parameter. | |
void | clearPlannerInstances () |
Remove all planner instances. | |
base::PlannerPtr & | getPlannerInstance (const std::size_t idx) |
Return an specific planner instance. | |
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. | |
base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) override |
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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true. | |
void | addSampler (const base::StateSamplerPtr &sampler) |
void | setFocusSearch (const bool focus) |
Option to control whether the search is focused during the search. | |
bool | getFocusSearch () const |
Get the state of the search focusing 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. | |
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. | |
virtual void | clearQuery () |
Clears internal datastructures of any query-specific information from the previous query. Planner settings are not affected. The planner, if able, should retain all datastructures generated from previous queries that can be used to help solve the next query. Note that clear() should also clear all query-specific information along with all other datastructures in the planner. By default clearQuery() calls clear(). | |
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. | |
Protected Member Functions | |
void | solve (base::Planner *planner, const base::PlannerTerminationCondition &ptc) |
Manages the call to solve() for each individual planner. | |
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 | |
base::OptimizationObjectivePtr | opt_ |
Optimization objective taken into account when planning. | |
std::vector< base::PlannerPtr > | planners_ |
The set of planners to be used. | |
std::vector< base::StateSamplerPtr > | samplers_ |
The set of sampler allocated by the planners. | |
std::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_ {0u} |
Number of paths shared among threads. | |
unsigned int | numStatesShared_ {0u} |
Number of states shared among threads. | |
std::mutex | newSolutionFoundMutex_ |
Mutex to control the access to the newSolutionFound() method. | |
std::mutex | addSamplerMutex_ |
Mutex to control the access to samplers_. | |
bool | focusSearch_ {true} |
Flag to control whether the search is focused. | |
unsigned int | numThreads_ |
Default number of threads to use when no planner instances are specified by the user. | |
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. | |
Additional Inherited Members | |
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. | |
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.
- 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
[PDF]
The documentation for this class was generated from the following files:
- ompl/geometric/planners/cforest/CForest.h
- ompl/geometric/planners/cforest/src/CForest.cpp