ompl::geometric::TRRT Class Reference

Transition-based Rapidly-exploring Random Trees. More...

#include <ompl/geometric/planners/rrt/TRRT.h>

Inheritance diagram for ompl::geometric::TRRT:

Classes

class  Motion
 Representation of a motion. More...
 

Public Member Functions

 TRRT (const base::SpaceInformationPtr &si)
 Constructor.
 
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 base::PlannerStatus solve (const base::PlannerTerminationCondition &plannerTerminationCondition)
 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. More...
 
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. More...
 
double getGoalBias () const
 Get the goal bias the planner is using.
 
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 setMaxStatesFailed (double maxStatesFailed)
 Set the maximum number of states that can be rejected before the temperature starts to rise.
 
double getMaxStatesFailed (void) const
 Get the maximum number of states that can be rejected before the temperature starts to rise.
 
void setTempChangeFactor (double tempChangeFactor)
 Set the factor by which the temperature rises or falls based on current acceptance/rejection rate.
 
double getTempChangeFactor (void) const
 Get the factor by which the temperature rises or falls based on current acceptance/rejection rate.
 
void setMinTemperature (double minTemperature)
 Set the minimum the temperature can drop to before being floored at that value.
 
double getMinTemperature (void) const
 Get the minimum the temperature can drop to before being floored at that value.
 
void setInitTemperature (double initTemperature)
 Set the initial temperature at the beginning of the algorithm. Should be low.
 
double getInitTemperature (void) const
 Get the initial temperature at the beginning of the algorithm. Should be low.
 
void setFrontierThreshold (double frontier_threshold)
 Set the distance between a new state and the nearest neighbor that qualifies that state as being a frontier.
 
double getFrontierThreshold (void) const
 Get the distance between a new state and the nearest neighbor that qualifies that state as being a frontier.
 
void setFrontierNodeRatio (double frontierNodeRatio)
 Set the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfrontier node for every 10 frontier nodes added.
 
double getFrontierNodeRatio (void) const
 Get the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfrontier node for every 10 frontier nodes added.
 
void setKConstant (double kConstant)
 Set the constant value used to normalize the expression.
 
double getKConstant (void) const
 Get the constant value used to normalize the expression.
 
template<template< typename T > class NN>
void setNearestNeighbors ()
 Set a different nearest neighbors datastructure.
 
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.
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const SpaceInformationPtr &si, const std::string &name)
 Constructor.
 
virtual ~Planner ()
 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.
 
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().
 
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.
 
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 freeMemory ()
 Free the memory allocated by this planner.
 
double distanceFunction (const Motion *a, const Motion *b) const
 Compute distance between motions (actually distance between contained states)
 
bool transitionTest (double childCost, double parentCost, double distance)
 Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree. More...
 
bool minExpansionControl (double randMotionDistance)
 Use ratio to prefer frontier nodes to nonfrontier ones.
 
- 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_
 State sampler.
 
boost::shared_ptr< NearestNeighbors< Motion * > > nearestNeighbors_
 A nearest-neighbors datastructure containing the tree of motions.
 
double goalBias_
 The fraction of time the goal is picked as the state to expand towards (if such a state is available)
 
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.
 
bool verbose_
 Output debug info.
 
double temp_
 Temperature parameter used to control the difficulty level of transition tests. Low temperatures limit the expansion to a slightly positive slopes, high temps enable to climb the steeper slopes. Dynamically tuned according to the information acquired during exploration.
 
double kConstant_
 Constant value used to normalize expression. Based on order of magnitude of the considered costs. Average cost of the query configurtaions since they are the only cost values known at the beginning of the search process.
 
unsigned int maxStatesFailed_
 Max number of rejections allowed.
 
double tempChangeFactor_
 Failure temperature factor used when max_num_failed_ failures occur.
 
double minTemperature_
 Prevent temperature from dropping too far.
 
double initTemperature_
 A very low value at initialization to authorize very easy positive slopes.
 
unsigned int numStatesFailed_
 Failure counter for states that are rejected.
 
double nonfrontierCount_
 Ratio counters for nodes that expand the search space versus those that do not.
 
double frontierCount_
 
double frontierThreshold_
 The distance between an old state and a new state that qualifies it as a frontier state.
 
double frontierNodeRatio_
 Target ratio of nonfrontier nodes to frontier nodes. rho.
 
ompl::base::OptimizationObjectivePtr opt_
 The optimization objective being optimized by TRRT.
 
- 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
typedef boost::function< std::string()> PlannerProgressProperty
 Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine.
 
typedef std::map< std::string, PlannerProgressPropertyPlannerProgressProperties
 A dictionary which maps the name of a progress property to the function to be used for querying that property.
 

Detailed Description

Transition-based Rapidly-exploring Random Trees.

Short description
T-RRT is an RRT variant and tree-based motion planner that takes into consideration state costs to compute low-cost paths that follow valleys and saddle points of the configuration-space costmap. It uses transition tests from stoachastic optimization methods to accept or reject new potential sates.
Example usage
Please see Dave Coleman's example to see how TRRT can be used.
External documentation
L. Jaillet, J. Cortés, T. Siméon, Sampling-Based Path Planning on Configuration-Space Costmaps, in IEEE TRANSACTIONS ON ROBOTICS, VOL. 26, NO. 4, AUGUST 2010. DOI: 10.1109/TRO.2010.2049527
[PDF]

Definition at line 77 of file TRRT.h.

Member Function Documentation

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

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

ompl::base::PlannerStatus ompl::geometric::TRRT::solve ( const base::PlannerTerminationCondition ptc)
virtual

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.

bool checkMotion(const State s1, const State *s2, std::pair<State, double> &lastValid) const Incrementally check if the path between two motions is valid. Also compute the last state that was valid and the time of that state. The time is used to parametrize the motion from s1 to s2, s1 being at t = 0 and s2 being at t = 1. This function assumes s1 is valid.

Parameters
s1start state of the motion to be checked (assumed to be valid)
s2final state of the motion to be checked

Implements ompl::base::Planner.

Definition at line 174 of file TRRT.cpp.

bool ompl::geometric::TRRT::transitionTest ( double  childCost,
double  parentCost,
double  distance 
)
protected

Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree.

Parameters
childCost- cost of current state
parentCost- cost of its ancestor parent state
distance- distance between parent and child

Definition at line 421 of file TRRT.cpp.


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