#include <time_indexed_rrt_connect.h>
|
| OMPLTimeIndexedRRTConnect (const base::SpaceInformationPtr &si) |
|
virtual | ~OMPLTimeIndexedRRTConnect () |
|
void | getPlannerData (base::PlannerData &data) const override |
|
base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) override |
|
void | clear () override |
|
void | setRange (double distance) |
| 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. More...
|
|
double | getRange () const |
| Get the range the planner is using. More...
|
|
template<template< typename T > class NN> |
void | setNearestNeighbors () |
| Set a different nearest neighbors datastructure. More...
|
|
void | setup () override |
|
◆ TreeData
A nearest-neighbor datastructure representing a tree of motions.
◆ GrowState
The state of the tree after an attempt to extend it.
Enumerator |
---|
TRAPPED | no progress has been made
|
ADVANCED | progress has been made towards the randomly sampled state
|
REACHED | the randomly sampled state was reached
|
◆ OMPLTimeIndexedRRTConnect()
exotica::OMPLTimeIndexedRRTConnect::OMPLTimeIndexedRRTConnect |
( |
const base::SpaceInformationPtr & |
si | ) |
|
◆ ~OMPLTimeIndexedRRTConnect()
virtual exotica::OMPLTimeIndexedRRTConnect::~OMPLTimeIndexedRRTConnect |
( |
| ) |
|
|
virtual |
◆ clear()
void exotica::OMPLTimeIndexedRRTConnect::clear |
( |
| ) |
|
|
override |
◆ correctTime()
bool exotica::OMPLTimeIndexedRRTConnect::correctTime |
( |
const Motion * |
a, |
|
|
Motion * |
b, |
|
|
bool |
reverse, |
|
|
bool & |
changed |
|
) |
| const |
|
inlineprotected |
◆ distanceFunction()
double exotica::OMPLTimeIndexedRRTConnect::distanceFunction |
( |
const Motion * |
a, |
|
|
const Motion * |
b |
|
) |
| const |
|
inlineprotected |
Compute distance between motions (actually distance between contained states)
◆ forwardTimeDistance()
double exotica::OMPLTimeIndexedRRTConnect::forwardTimeDistance |
( |
const Motion * |
a, |
|
|
const Motion * |
b |
|
) |
| const |
|
inlineprotected |
◆ freeMemory()
void exotica::OMPLTimeIndexedRRTConnect::freeMemory |
( |
| ) |
|
|
protected |
Free the memory allocated by this planner.
◆ getPlannerData()
void exotica::OMPLTimeIndexedRRTConnect::getPlannerData |
( |
base::PlannerData & |
data | ) |
const |
|
override |
◆ getRange()
double exotica::OMPLTimeIndexedRRTConnect::getRange |
( |
| ) |
const |
|
inline |
Get the range the planner is using.
◆ growTree()
Grow a tree towards a random state.
◆ reverseTimeDistance()
double exotica::OMPLTimeIndexedRRTConnect::reverseTimeDistance |
( |
const Motion * |
a, |
|
|
const Motion * |
b |
|
) |
| const |
|
inlineprotected |
◆ setNearestNeighbors()
template<template< typename T > class NN>
void exotica::OMPLTimeIndexedRRTConnect::setNearestNeighbors |
( |
| ) |
|
|
inline |
Set a different nearest neighbors datastructure.
◆ setRange()
void exotica::OMPLTimeIndexedRRTConnect::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.
◆ setup()
void exotica::OMPLTimeIndexedRRTConnect::setup |
( |
| ) |
|
|
override |
◆ solve()
base::PlannerStatus exotica::OMPLTimeIndexedRRTConnect::solve |
( |
const base::PlannerTerminationCondition & |
ptc | ) |
|
|
override |
◆ connectionPoint_
std::pair<base::State *, base::State *> exotica::OMPLTimeIndexedRRTConnect::connectionPoint_ |
|
protected |
The pair of states in each tree connected during planning. Used for PlannerData computation.
◆ maxDistance_
double exotica::OMPLTimeIndexedRRTConnect::maxDistance_ |
|
protected |
The maximum length of a motion to be added to a tree.
◆ reverse_check_
bool exotica::OMPLTimeIndexedRRTConnect::reverse_check_ |
|
protected |
◆ rng_
RNG exotica::OMPLTimeIndexedRRTConnect::rng_ |
|
protected |
The random number generator.
◆ sampler_
base::StateSamplerPtr exotica::OMPLTimeIndexedRRTConnect::sampler_ |
|
protected |
◆ tGoal_
TreeData exotica::OMPLTimeIndexedRRTConnect::tGoal_ |
|
protected |
◆ tStart_
TreeData exotica::OMPLTimeIndexedRRTConnect::tStart_ |
|
protected |
The documentation for this class was generated from the following file:
- /tmp/exotica/exotations/solvers/exotica_time_indexed_rrt_connect_solver/include/exotica_time_indexed_rrt_connect_solver/time_indexed_rrt_connect.h