Lazy Bi-directional KPIECE with one level of discretization. More...

#include <ompl/geometric/planners/kpiece/LBKPIECE1.h>

Inheritance diagram for ompl::geometric::LBKPIECE1:

Classes

class  Motion
 Representation of a motion for this algorithm. More...
 

Public Member Functions

 LBKPIECE1 (const base::SpaceInformationPtr &si)
 Constructor.
 
void setProjectionEvaluator (const base::ProjectionEvaluatorPtr &projectionEvaluator)
 Set the projection evaluator. This class is able to compute the projection of a given state.
 
void setProjectionEvaluator (const std::string &name)
 Set the projection evaluator (select one from the ones registered with the state space).
 
const base::ProjectionEvaluatorPtr & getProjectionEvaluator () const
 Get the projection evaluator.
 
void setRange (double distance)
 Set the range the planner is supposed to use. More...
 
double getRange () const
 Get the range the planner is using.
 
void setBorderFraction (double bp)
 Set the fraction of time for focusing on the border (between 0 and 1). This is the minimum fraction used to select cells that are exterior (minimum because if 95% of cells are on the border, they will be selected with 95% chance, even if this fraction is set to 90%)
 
double getBorderFraction () const
 Get the fraction of time to focus exploration on boundary.
 
void setMinValidPathFraction (double fraction)
 When extending a motion, the planner can decide to keep the first valid part of it, even if invalid states are found, as long as the valid part represents a sufficiently large fraction from the original motion. This function sets the minimum acceptable fraction.
 
double getMinValidPathFraction () const
 Get the value of the fraction set by setMinValidPathFraction()
 
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 clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
 
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).

 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (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 SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
 
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
 
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
 
const PlannerInputStatesgetPlannerInputStates () 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 PlannerSpecsgetSpecs () 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.
 
ParamSetparams ()
 Get the parameters for this planner.
 
const ParamSetparams () const
 Get the parameters for this planner.
 
const PlannerProgressPropertiesgetPlannerProgressProperties () 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 freeMotion (Motion *motion)
 Free the memory for a motion.
 
void removeMotion (Discretization< Motion > &disc, Motion *motion)
 Remove a motion from a tree of motions.
 
bool isPathValid (Discretization< Motion > &disc, Motion *motion, base::State *temp)
 Since solutions are computed in a lazy fashion, once trees are connected, the solution found needs to be checked for validity. This function checks whether the reverse path from a given motion to a root is valid. If this is not the case, invalid motions are removed

 
- 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::StateSamplerPtr sampler_
 The employed state sampler.
 
base::ProjectionEvaluatorPtr projectionEvaluator_
 The employed projection evaluator.
 
Discretization< MotiondStart_
 The start tree.
 
Discretization< MotiondGoal_
 The goal tree.
 
double minValidPathFraction_ {0.5}
 When extending a motion, the planner can decide to keep the first valid part of it, even if invalid states are found, as long as the valid part represents a sufficiently large fraction from the original motion.
 
double maxDistance_ {0.}
 The maximum length of a motion to be added to a tree.
 
RNG rng_
 The random number generator.
 
std::pair< base::State *, base::State * > connectionPoint_ {nullptr, nullptr}
 The pair of states in each tree connected during planning. Used for PlannerData computation.
 
- 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

Lazy Bi-directional KPIECE with one level of discretization.

Short description
KPIECE is a tree-based planner that uses a discretization (multiple levels, in general) to guide the exploration of the continuous space. This implementation is a simplified one, using a single level of discretization: one grid. The grid is imposed on a projection of the state space. When exploring the space, preference is given to the boundary of this grid. The boundary is computed to be the set of grid cells that have less than 2n non-diagonal neighbors in an n-dimensional projection space. It is important to set the projection the algorithm uses (setProjectionEvaluator() function). If no projection is set, the planner will attempt to use the default projection associated to the state space. An exception is thrown if no default projection is available either. This variant of the implementation use two trees of exploration with lazy collision checking, hence the LB prefix.
External documentation
  • I.A. Şucan and L.E. Kavraki, Kinodynamic motion planning by interior-exterior cell exploration, in Workshop on the Algorithmic Foundations of Robotics, Dec. 2008.
    [PDF]
  • R. Bohlin and L.E. Kavraki, Path planning using lazy PRM, in Proc. 2000 IEEE Intl. Conf. on Robotics and Automation, pp. 521–528, 2000. DOI: 10.1109/ROBOT.2000.844107
    [PDF]

Definition at line 142 of file LBKPIECE1.h.

Member Function Documentation

◆ setRange()

void ompl::geometric::LBKPIECE1::setRange ( double  distance)
inline

Set the range the planner is supposed to use.

This parameter greatly influences the runtime of the algorithm. It represents the maximum length of a motion to be added in the tree of motions.

Definition at line 207 of file LBKPIECE1.h.


The documentation for this class was generated from the following files: