|
| VFRRT (const base::SpaceInformationPtr &si, VectorField vf, double exploration, double initial_lambda, unsigned int update_freq) |
|
| ~VFRRT () override |
|
void | clear () override |
|
double | determineMeanNorm () |
|
Eigen::VectorXd | getNewDirection (const base::State *qnear, const base::State *qrand) |
|
double | biasedSampling (const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield, double lambdaScale) |
|
void | updateGain () |
|
Eigen::VectorXd | computeAlphaBeta (double omega, const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield) |
|
Motion * | extendTree (Motion *m, base::State *rstate, const Eigen::VectorXd &v) |
|
void | updateExplorationEfficiency (Motion *m) |
|
base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) override |
|
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.
|
|
| RRT (const base::SpaceInformationPtr &si, bool addIntermediateStates=false) |
| Constructor.
|
|
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 | setGoalBias (double goalBias) |
| Set the goal bias. More...
|
|
double | getGoalBias () const |
| Get the goal bias the planner is using.
|
|
bool | getIntermediateStates () const |
| Return true if the intermediate states generated along motions are to be added to the tree itself.
|
|
void | setIntermediateStates (bool addIntermediateStates) |
| Specify whether the intermediate states generated along motions are to be added to the tree itself.
|
|
void | setRange (double distance) |
| Set the range the planner is supposed to use. More...
|
|
double | getRange () const |
| Get the range the planner is using.
|
|
template<template< typename T > class NN> |
void | setNearestNeighbors () |
| Set a different nearest neighbors datastructure.
|
|
| 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.
|
|
|
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)
|
|
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.
|
|
base::StateSamplerPtr | sampler_ |
| State sampler.
|
|
std::shared_ptr< NearestNeighbors< Motion * > > | nn_ |
| A nearest-neighbors datastructure containing the tree of motions.
|
|
double | goalBias_ {.05} |
| The fraction of time the goal is picked as the state to expand towards (if such a state is available)
|
|
double | maxDistance_ {0.} |
| The maximum length of a motion to be added to a tree.
|
|
bool | addIntermediateStates_ |
| Flag indicating whether intermediate states are added to the built tree of motions.
|
|
RNG | rng_ |
| The random number generator.
|
|
Motion * | lastGoalMotion_ {nullptr} |
| The most recent goal motion. Used for PlannerData computation.
|
|
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.
|
|
- Short description
- Vector Field Rapidly-exploring Random Tree (VFRRT) is a tree-based motion planner that tries to minimize the so-called upstream cost of a path. The upstream cost is defined by an integral over a user-defined vector field.
- External documentation
- I. Ko, B. Kim, and F. C. Park, Randomized path planning on vector fields, Intl. J. of Robotics Research, 33(13), pp. 1664–1682, 2014. DOI: 10.1177/0278364914545812
[PDF]
Definition at line 130 of file VFRRT.h.