Class VFRRT
Defined in File VFRRT.h
Inheritance Relationships
Base Type
public ompl::geometric::RRT
(Class RRT)
Class Documentation
-
class VFRRT : public ompl::geometric::RRT
- 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
Public Functions
-
VFRRT(const base::SpaceInformationPtr &si, VectorField vf, double exploration, double initial_lambda, unsigned int update_freq)
Constructor.
-
~VFRRT() override
Destructor.
-
virtual void clear() override
Reset internal data.
-
double determineMeanNorm()
Make a Monte Carlo estimate for the mean vector norm in the field.
-
Eigen::VectorXd getNewDirection(const base::State *qnear, const base::State *qrand)
Use the vector field to alter the direction of a sample.
-
double biasedSampling(const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield, double lambdaScale)
Calculates the weight omega which can be used to compute alpha and beta.
-
void updateGain()
Every nth time this function is called (where the nth step is the update frequency given in the constructor) the value of lambda is updated and the counts of efficient and inefficient samples added to the tree are reset to 0. The measure for exploration inefficiency is also reset to 0.
-
Eigen::VectorXd computeAlphaBeta(double omega, const Eigen::VectorXd &vrand, const Eigen::VectorXd &vfield)
Computes alpha and beta, using these values to produce the vector returned by getNewDirection. This produced vector can be used to determine the direction an added state should be to maximize the upstream criterion of the produced path.
-
Motion *extendTree(Motion *m, base::State *rstate, const Eigen::VectorXd &v)
This attempts to extend the tree from the motion m to a new motion in the direction specified by the vector v.
-
void updateExplorationEfficiency(Motion *m)
Updates measures for exploration efficiency if a given motion m is added to the nearest NearestNeighbors structure.
-
virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Solve the planning problem.
-
virtual 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.