ompl::geometric::KPIECE1 Class Reference

Kinematic Planning by Interior-Exterior Cell Exploration. More...

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

Inheritance diagram for ompl::geometric::KPIECE1:

List of all members.

Classes

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

Public Member Functions

 KPIECE1 (const base::SpaceInformationPtr &si)
 Constructor.
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.
virtual void clear ()
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
void setGoalBias (double goalBias)
 Set the goal bias.
double getGoalBias () const
 Get the goal bias the planner is using.
void setRange (double distance)
 Set the range the planner is supposed to use.
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 (between 0 and 1).
double getMinValidPathFraction () const
 Get the value of the fraction set by setMinValidPathFraction()
void setFailedExpansionCellScoreFactor (double factor)
 When extending a motion from a cell, the extension can be successful or it can fail. If the extension fails, the score of the cell is multiplied by factor. These number should be in the range (0, 1].
double getFailedExpansionCellScoreFactor () const
 Get the factor that is multiplied to a cell's score if extending a motion from that cell failed.
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.
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 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).

Protected Member Functions

void freeMotion (Motion *motion)
 Free the memory for a motion.

Protected Attributes

base::StateSamplerPtr sampler_
 A state space sampler.
Discretization< Motiondisc_
 The tree datastructure and the grid that covers it.
base::ProjectionEvaluatorPtr projectionEvaluator_
 This algorithm uses a discretization (a grid) to guide the exploration. The exploration is imposed on a projection of the state space.
double failedExpansionScoreFactor_
 When extending a motion from a cell, the extension can fail. If it is, the score of the cell is multiplied by this factor.
double goalBias_
 The fraction of time the goal is picked as the state to expand towards (if such a state is available)
double minValidPathFraction_
 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_
 The maximum length of a motion to be added to a tree.
RNG rng_
 The random number generator.
MotionlastGoalMotion_
 The most recent goal motion. Used for PlannerData computation.

Detailed Description

Kinematic Planning by Interior-Exterior Cell Exploration.

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.
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]](http://ioan.sucan.ro/files/pubs/wafr2008.pdf)

Definition at line 74 of file KPIECE1.h.


Member Function Documentation

void ompl::geometric::KPIECE1::setGoalBias ( double  goalBias) [inline]

Set the goal bias.

In the process of randomly selecting states in the state space to attempt to go towards, the algorithm may in fact choose the actual goal state, if it knows it, with some probability. This probability is a real number between 0.0 and 1.0; its value should usually be around 0.05 and should not be too large. It is probably a good idea to use the default value.

Definition at line 96 of file KPIECE1.h.

void ompl::geometric::KPIECE1::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 112 of file KPIECE1.h.


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