Aikido
|
Implements a bi-direction constrained RRT planner. More...
#include <aikido/planner/ompl/CRRTConnect.hpp>
Public Member Functions | |
CRRTConnect (const ::ompl::base::SpaceInformationPtr &si) | |
Constructor. More... | |
virtual | ~CRRTConnect () |
Destructor. More... | |
void | getPlannerData (::ompl::base::PlannerData &_data) const override |
Get information about the current run of the motion planner. More... | |
::ompl::base::PlannerStatus | solve (const ::ompl::base::PlannerTerminationCondition &_ptc) override |
Function that can solve the motion planning problem. More... | |
::ompl::base::PlannerStatus | solve (double _solveTime) |
Solve the motion planning problem in the given time. More... | |
void | clear () override |
Clear all internal datastructures. More... | |
void | setConnectionRadius (double _radius) |
double | getConnectionRadius () const |
Get the connection radius the planner is using. More... | |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
Set a nearest neighbors data structure for both the start and goal trees. More... | |
void | setup () override |
Perform extra configuration steps, if needed. More... | |
![]() | |
CRRT (const ::ompl::base::SpaceInformationPtr &_si) | |
Constructor. More... | |
CRRT (const ::ompl::base::SpaceInformationPtr &_si, const std::string &_name) | |
Constructor. More... | |
virtual | ~CRRT () |
Destructor. More... | |
void | getPlannerData (::ompl::base::PlannerData &_data) const override |
Get information about the current run of the motion planner. More... | |
::ompl::base::PlannerStatus | solve (const ::ompl::base::PlannerTerminationCondition &_ptc) override |
Function that can solve the motion planning problem. More... | |
::ompl::base::PlannerStatus | solve (double _solveTime) |
Solve the motion planning problem in the given time. More... | |
void | clear () override |
Clear all internal datastructures. More... | |
void | setGoalBias (double _goalBias) |
Set the goal bias. More... | |
double | getGoalBias () const |
Get the goal bias the planner is using. More... | |
void | setRange (double _distance) |
Set the range the planner is supposed to use. More... | |
double | getRange () const |
Get the range the planner is using. More... | |
void | setPathConstraint (constraint::ProjectablePtr _projectable) |
Set a projectable constraint to be applied throughout the trajectory. More... | |
void | setProjectionResolution (double _resolution) |
Set the resolution for the projection. More... | |
double | getProjectionResolution () const |
Get the resolution for the projection. More... | |
void | setMinStateDifference (double _mindist) |
Set the minimum distance between two states for them to be considered "equivalent". More... | |
double | getMinStateDifference () const |
Get the minimum distance between two states for them to be considered "equivalent". More... | |
template<template< typename T > class NN> | |
void | setNearestNeighbors () |
Set a nearest neighbors data structure. More... | |
void | setup () override |
Perform extra configuration steps, if needed. More... | |
Protected Member Functions | |
void | freeMemory () override |
Free the memory allocated by this planner. More... | |
![]() | |
double | distanceFunction (const Motion *a, const Motion *b) const |
Compute distance between motions (actually distance between contained states. More... | |
Motion * | constrainedExtend (const ::ompl::base::PlannerTerminationCondition &ptc, TreeData &tree, Motion *nmotion, ::ompl::base::State *gstate, ::ompl::base::State *xstate, ::ompl::base::Goal *goal, bool returnlast, double &dist, bool &foundgoal) |
Perform an extension that projects to a constraint. More... | |
Protected Attributes | |
TreeData | mGoalTree |
The goal tree. More... | |
double | mConnectionRadius |
Max distance between two trees to consider them connected. More... | |
std::pair<::ompl::base::State *, ::ompl::base::State * > | mConnectionPoint |
The pair of states in each tree connected during planning. More... | |
![]() | |
TreeData | mStartTree |
A nearest-neighbors datastructure containing the tree of motions. More... | |
::ompl::base::StateSamplerPtr | mSampler |
State sampler. More... | |
double | mGoalBias |
The fraction of time the goal is picked as the state to expand towards (if such a state is available) More... | |
double | mMaxDistance |
The maximum length of a motion to be added to a tree. More... | |
::ompl::RNG | mRng |
The random number generator used to determine whether to sample a goal state or a state uniformly from free space. More... | |
Motion * | mLastGoalMotion |
The most recent goal motion. Used for PlannerData computation. More... | |
constraint::ProjectablePtr | mCons |
The constraint that must be satisfied throughout the trajectory. More... | |
double | mMaxStepsize |
The maximum length of a step before projecting. More... | |
double | mMinStepsize |
The minumum step size along the constraint. More... | |
Additional Inherited Members | |
![]() | |
using | TreeData = ompl_shared_ptr<::ompl::NearestNeighbors< Motion * > > |
A nearest-neighbor datastructure representing a tree of motions */. More... | |
Implements a bi-direction constrained RRT planner.
|
explicit |
Constructor.
si | Information about the planning instance |
|
virtual |
Destructor.
|
override |
|
overrideprotectedvirtual |
Free the memory allocated by this planner.
Reimplemented from aikido::planner::ompl::CRRT.
double aikido::planner::ompl::CRRTConnect::getConnectionRadius | ( | ) | const |
Get the connection radius the planner is using.
|
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).
[out] | _data | Data about the current run of the motion planner |
void aikido::planner::ompl::CRRTConnect::setConnectionRadius | ( | double | _radius | ) |
_radius | The maximum distance between two trees for them to be considered connected |
void aikido::planner::ompl::CRRTConnect::setNearestNeighbors |
Set a nearest neighbors data structure for both the start and goal trees.
|
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.
|
override |
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.
_ptc | Conditions for terminating planning before a solution is found |
::ompl::base::PlannerStatus aikido::planner::ompl::CRRTConnect::solve | ( | double | _solveTime | ) |
Solve the motion planning problem in the given time.
_solveTime | The maximum allowable time to solve the planning problem |
|
protected |
The pair of states in each tree connected during planning.
Use for PlannerData computation
|
protected |
Max distance between two trees to consider them connected.
|
protected |
The goal tree.