Aikido
aikido::planner::ompl::CRRTConnect Class Reference

Implements a bi-direction constrained RRT planner. More...

#include <aikido/planner/ompl/CRRTConnect.hpp>

Inheritance diagram for aikido::planner::ompl::CRRTConnect:
aikido::planner::ompl::CRRT

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...
 
- Public Member Functions inherited from aikido::planner::ompl::CRRT
 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...
 
- Protected Member Functions inherited from aikido::planner::ompl::CRRT
double distanceFunction (const Motion *a, const Motion *b) const
 Compute distance between motions (actually distance between contained states. More...
 
MotionconstrainedExtend (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...
 
- Protected Attributes inherited from aikido::planner::ompl::CRRT
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...
 
MotionmLastGoalMotion
 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

- Protected Types inherited from aikido::planner::ompl::CRRT
using TreeData = ompl_shared_ptr<::ompl::NearestNeighbors< Motion * > >
 A nearest-neighbor datastructure representing a tree of motions *‍/. More...
 

Detailed Description

Implements a bi-direction constrained RRT planner.

Constructor & Destructor Documentation

◆ CRRTConnect()

aikido::planner::ompl::CRRTConnect::CRRTConnect ( const ::ompl::base::SpaceInformationPtr &  si)
explicit

Constructor.

Parameters
siInformation about the planning instance

◆ ~CRRTConnect()

virtual aikido::planner::ompl::CRRTConnect::~CRRTConnect ( )
virtual

Destructor.

Member Function Documentation

◆ clear()

void aikido::planner::ompl::CRRTConnect::clear ( )
override

Clear all internal datastructures.

Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.

◆ freeMemory()

void aikido::planner::ompl::CRRTConnect::freeMemory ( )
overrideprotectedvirtual

Free the memory allocated by this planner.

Reimplemented from aikido::planner::ompl::CRRT.

◆ getConnectionRadius()

double aikido::planner::ompl::CRRTConnect::getConnectionRadius ( ) const

Get the connection radius the planner is using.

◆ getPlannerData()

void aikido::planner::ompl::CRRTConnect::getPlannerData ( ::ompl::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).

Parameters
[out]_dataData about the current run of the motion planner

◆ setConnectionRadius()

void aikido::planner::ompl::CRRTConnect::setConnectionRadius ( double  _radius)
Parameters
_radiusThe maximum distance between two trees for them to be considered connected

◆ setNearestNeighbors()

template<template< typename T > class NN>
void aikido::planner::ompl::CRRTConnect::setNearestNeighbors

Set a nearest neighbors data structure for both the start and goal trees.

◆ setup()

void aikido::planner::ompl::CRRTConnect::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.

◆ solve() [1/2]

::ompl::base::PlannerStatus aikido::planner::ompl::CRRTConnect::solve ( const ::ompl::base::PlannerTerminationCondition &  _ptc)
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.

Parameters
_ptcConditions for terminating planning before a solution is found

◆ solve() [2/2]

::ompl::base::PlannerStatus aikido::planner::ompl::CRRTConnect::solve ( double  _solveTime)

Solve the motion planning problem in the given time.

Parameters
_solveTimeThe maximum allowable time to solve the planning problem

Member Data Documentation

◆ mConnectionPoint

std::pair<::ompl::base::State*, ::ompl::base::State*> aikido::planner::ompl::CRRTConnect::mConnectionPoint
protected

The pair of states in each tree connected during planning.

Use for PlannerData computation

◆ mConnectionRadius

double aikido::planner::ompl::CRRTConnect::mConnectionRadius
protected

Max distance between two trees to consider them connected.

◆ mGoalTree

TreeData aikido::planner::ompl::CRRTConnect::mGoalTree
protected

The goal tree.