Loading...
Searching...
No Matches

Hybrid Rapidly-exploring Random Trees. More...

#include <ompl/control/planners/rrt/HyRRT.h>

Inheritance diagram for ompl::control::HyRRT:

Classes

class  Motion
 Representation of a motion in the search tree. More...

Public Member Functions

 HyRRT (const control::SpaceInformationPtr &si)
 Constructor.
 ~HyRRT () override
 Destructor.
void clear () override
 Clear all allocated memory.
void setup () override
 Set the problem instance to solve.
void getPlannerData (base::PlannerData &data) const override
 Get the PlannerData object associated with this planner.
base::PlannerStatus solve (const 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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.
void freeMemory ()
 Free the memory allocated by this planner.
void setTm (double tM)
 Set the maximum time allocated to a full continuous simulator step.
void setFlowStepDuration (double duration)
 Set the time allocated to a single continuous simulator call, within the full period of a continuous simulator step.
void setJumpSet (std::function< bool(Motion *motion)> jumpSet)
 Define the jump set.
void setFlowSet (std::function< bool(Motion *motion)> flowSet)
 Define the flow set.
void setUnsafeSet (std::function< bool(Motion *motion)> unsafeSet)
 Define the unsafe set.
void setDistanceFunction (std::function< double(base::State *, base::State *)> function)
 Define the distance measurement function.
void setDiscreteSimulator (std::function< base::State *(base::State *curState, const control::Control *u, base::State *newState)> function)
 Define the discrete dynamics simulator.
void setCollisionChecker (std::function< bool(Motion *motion, std::function< bool(Motion *motion)> obstacleSet, base::State *newState, double *collisionTime)> function)
 Define the collision checker.
template<template< typename T > class NN>
void setNearestNeighbors (void)
 Set a different nearest neighbors datastructure.
void checkMandatoryParametersSet (void) const
 Check if all required parameters have been set.
Public Member Functions inherited from ompl::base::Planner
 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.
template<class T>
const T * as () const
 Cast this instance to a desired type.
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
const PlannerInputStatesgetPlannerInputStates () 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 PlannerSpecsgetSpecs () 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.
ParamSetparams ()
 Get the parameters for this planner.
const ParamSetparams () const
 Get the parameters for this planner.
const PlannerProgressPropertiesgetPlannerProgressProperties () 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.

Public Attributes

std::function< ompl::base::State *(const control::Control *control, ompl::base::State *x_cur, double tFlow, ompl::base::State *new_state)> continuousSimulator
 Simulates the dynamics of the multicopter when in flow regime, with no nonnegligble forces other than input acceleration.

Protected Member Functions

void setContinuousSimulator (std::function< base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> function)
 Define the continuous dynamics simulator.
void initTree (void)
 Runs the initial setup tasks for the tree.
void randomSample (Motion *randomMotion)
 Sample the random motion.
base::PlannerStatus constructSolution (Motion *lastMotion)
 Construct the path, starting at the last edge.
Protected Member Functions inherited from ompl::base::Planner
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.

Static Protected Member Functions

static const ompl::control::ControlgetFlowControl (const ompl::control::Control *control)
static const ompl::control::ControlgetJumpControl (const ompl::control::Control *control)

Protected Attributes

MotionlastGoalMotion_ {nullptr}
 The most recent goal motion. Used for PlannerData computation.
std::shared_ptr< NearestNeighbors< Motion * > > nn_
 A nearest-neighbors datastructure containing the tree of motions.
std::function< bool(Motion *motion, std::function< bool(Motion *motion)> obstacleSet, base::State *newState, double *collisionTime)> collisionChecker_
 Collision checker. Default is point-by-point collision checking using the jump set.
control::DirectedControlSamplerPtr controlSampler_
 Control Sampler.
control::SpaceInformationsiC_
 The base::SpaceInformation cast as control::SpaceInformation, for convenience.
std::function< double(base::State *state1, base::State *state2)> distanceFunc_
 Compute distance between states, default is Euclidean distance.
double tM_
 The maximum flow time for a given flow propagation step. Must be set by the user.
double flowStepDuration_
 The flow time for a given integration step, within a flow propagation step. Must be set by user.
std::function< base::State *(base::State *curState, const control::Control *u, base::State *newState)> discreteSimulator_
 Simulator for propagation under jump regime.
std::function< bool(Motion *motion)> jumpSet_
 Function that returns true if a motion intersects with the jump set, and false if not.
std::function< bool(Motion *motion)> flowSet_
 Function that returns true if a motion intersects with the flow set, and false if not.
std::function< bool(Motion *motion)> unsafeSet_
 Function that returns true if a motion intersects with the unsafe set, and false if not.
std::function< base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> continuousSimulator_
 Simulator for propagation under flow regime.
base::StateSamplerPtr sampler_
 State sampler.
double dist_
 Minimum distance from goal to final vertex of generated trajectories.
Protected Attributes inherited from ompl::base::Planner
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.

Additional Inherited Members

Public Types inherited from ompl::base::Planner
using PlannerProgressProperty = std::function<std::string()>
 Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine.
using PlannerProgressProperties = std::map<std::string, PlannerProgressProperty>
 A dictionary which maps the name of a progress property to the function to be used for querying that property.

Detailed Description

Hybrid Rapidly-exploring Random Trees.

Hybrid RRT (HyRRT) is an RRT algorithm that solves separate optimization
problems associated with the flows and jumps of the systems, to solve a variety of robotic motion planning problems. As an RRT algorithm, HyRRT is probabilistically-complete. The logical flow of the algorithm is as follows:
  1. Initialize the tree with a start state.
  2. While a solution has not been found: a. Sample a random state. b. Find the nearest state in the tree to the random state. c. Extend from that state under either the flow or jump regimes, using the continuous or discrete simulators, respectively. d. Continue until the state is in collision, or the maximum flow time has been exceeded. e. If the state is not within the unsafe set, add the state to the tree. If the state is in collision, proceed to jump.
    1. Return the solution.
External documentation: https://ieeexplore.ieee.org/document/9992444
DOI: [10.1109/CDC51059.2022.9992444]

Definition at line 76 of file HyRRT.h.

Constructor & Destructor Documentation

◆ HyRRT()

ompl::control::HyRRT::HyRRT ( const control::SpaceInformationPtr & si)

Constructor.

Definition at line 50 of file HyRRT.cpp.

◆ ~HyRRT()

ompl::control::HyRRT::~HyRRT ( )
override

Destructor.

Definition at line 56 of file HyRRT.cpp.

Member Function Documentation

◆ checkMandatoryParametersSet()

void ompl::control::HyRRT::checkMandatoryParametersSet ( void ) const
inline

Check if all required parameters have been set.

Definition at line 255 of file HyRRT.h.

◆ clear()

void ompl::control::HyRRT::clear ( )
overridevirtual

Clear all allocated memory.

Reimplemented from ompl::base::Planner.

Definition at line 312 of file HyRRT.cpp.

◆ constructSolution()

base::PlannerStatus ompl::control::HyRRT::constructSolution ( Motion * lastMotion)
protected

Construct the path, starting at the last edge.

Parameters
lastMotionThe last motion in the solution
Returns
the planner status (APPROXIMATE, EXACT, or UNKNOWN)

Definition at line 254 of file HyRRT.cpp.

◆ freeMemory()

void ompl::control::HyRRT::freeMemory ( void )

Free the memory allocated by this planner.

Definition at line 332 of file HyRRT.cpp.

◆ getFlowControl()

const ompl::control::Control * ompl::control::HyRRT::getFlowControl ( const ompl::control::Control * control)
inlinestaticprotected

Definition at line 283 of file HyRRT.h.

◆ getJumpControl()

const ompl::control::Control * ompl::control::HyRRT::getJumpControl ( const ompl::control::Control * control)
inlinestaticprotected

Definition at line 288 of file HyRRT.h.

◆ getPlannerData()

void ompl::control::HyRRT::getPlannerData ( base::PlannerData & data) const
overridevirtual

Get the PlannerData object associated with this planner.

Parameters
datathe PlannerData object storing the edges and vertices of the solution

Reimplemented from ompl::base::Planner.

Definition at line 354 of file HyRRT.cpp.

◆ initTree()

void ompl::control::HyRRT::initTree ( void )
protected

Runs the initial setup tasks for the tree.

Definition at line 61 of file HyRRT.cpp.

◆ randomSample()

void ompl::control::HyRRT::randomSample ( Motion * randomMotion)
protected

Sample the random motion.

Parameters
randomMotionThe motion to be initialized

Definition at line 82 of file HyRRT.cpp.

◆ setCollisionChecker()

void ompl::control::HyRRT::setCollisionChecker ( std::function< bool(Motion *motion, std::function< bool(Motion *motion)> obstacleSet, base::State *newState, double *collisionTime)> function)
inline

Define the collision checker.

Parameters
functionthe collision checker associated with the state space. Default is a point-by-point collision checker.

Definition at line 236 of file HyRRT.h.

◆ setContinuousSimulator()

void ompl::control::HyRRT::setContinuousSimulator ( std::function< base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> function)
inlineprotected

Define the continuous dynamics simulator.

Parameters
functionthe continuous simulator associated with the hybrid system.

Definition at line 276 of file HyRRT.h.

◆ setDiscreteSimulator()

void ompl::control::HyRRT::setDiscreteSimulator ( std::function< base::State *(base::State *curState, const control::Control *u, base::State *newState)> function)
inline

Define the discrete dynamics simulator.

Parameters
functionthe discrete simulator associated with the hybrid system.

Definition at line 213 of file HyRRT.h.

◆ setDistanceFunction()

void ompl::control::HyRRT::setDistanceFunction ( std::function< double(base::State *, base::State *)> function)
inline

Define the distance measurement function.

Parameters
functionthe distance function associated with the motion planning problem.

Definition at line 204 of file HyRRT.h.

◆ setFlowSet()

void ompl::control::HyRRT::setFlowSet ( std::function< bool(Motion *motion)> flowSet)
inline

Define the flow set.

Parameters
flowSetthe flow set associated with the hybrid system.

Definition at line 186 of file HyRRT.h.

◆ setFlowStepDuration()

void ompl::control::HyRRT::setFlowStepDuration ( double duration)
inline

Set the time allocated to a single continuous simulator call, within the full period of a continuous simulator step.

Parameters
durationthe time allocated per simulator step. Must be greater than 0 and less than the time allocated to a full continuous simulator step.

Definition at line 160 of file HyRRT.h.

◆ setJumpSet()

void ompl::control::HyRRT::setJumpSet ( std::function< bool(Motion *motion)> jumpSet)
inline

Define the jump set.

Parameters
jumpSetthe jump set associated with the hybrid system.

Definition at line 177 of file HyRRT.h.

◆ setNearestNeighbors()

template<template< typename T > class NN>
void ompl::control::HyRRT::setNearestNeighbors ( void )
inline

Set a different nearest neighbors datastructure.

Definition at line 245 of file HyRRT.h.

◆ setTm()

void ompl::control::HyRRT::setTm ( double tM)
inline

Set the maximum time allocated to a full continuous simulator step.

Parameters
tMthe maximum time allocated. Must be greater than 0, and greater than than the time allocated to a single continuous simulator call.

Definition at line 139 of file HyRRT.h.

◆ setUnsafeSet()

void ompl::control::HyRRT::setUnsafeSet ( std::function< bool(Motion *motion)> unsafeSet)
inline

Define the unsafe set.

Parameters
unsafeSetthe unsafe set associated with the hybrid system.

Definition at line 195 of file HyRRT.h.

◆ setup()

void ompl::control::HyRRT::setup ( )
overridevirtual

Set the problem instance to solve.

Reimplemented from ompl::base::Planner.

Definition at line 322 of file HyRRT.cpp.

◆ solve()

base::PlannerStatus ompl::control::HyRRT::solve ( const base::PlannerTerminationCondition & ptc)
overridevirtual

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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.

Implements ompl::base::Planner.

Definition at line 87 of file HyRRT.cpp.

Member Data Documentation

◆ collisionChecker_

std::function<bool(Motion *motion, std::function<bool(Motion *motion)> obstacleSet, base::State *newState, double *collisionTime)> ompl::control::HyRRT::collisionChecker_
protected
Initial value:
= [this](Motion *motion, std::function<bool(Motion *motion)> obstacleSet,
base::State *newState, double *collisionTime) -> bool
{
if (obstacleSet(motion))
{
si_->copyState(newState, motion->solutionPair->back());
*collisionTime =
motion->solutionPair->resize(motion->solutionPair->size() - 1);
return true;
}
return false;
}
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
Definition of an abstract state.
Definition State.h:50
Representation of a motion in the search tree.
Definition HyRRT.h:100
double flowStepDuration_
The flow time for a given integration step, within a flow propagation step. Must be set by user.
Definition HyRRT.h:360

Collision checker. Default is point-by-point collision checking using the jump set.

The following are all customizeable parameters, and affect how cHyRRT generates trajectories. Customize using setter functions above.

Parameters
motionThe motion to check for collision
obstacleSetA function that returns true if the motion's solution pair intersects with the obstacle set
tsThe start time of the motion. Default is -1.0
tfThe end time of the motion. Default is -1.0
newStateThe collision state (if a collision occurs)
collisionTimeThe time of collision (if a collision occurs). If no collision occurs, this value is -1.0
Returns
true if a collision occurs, false otherwise

Definition at line 327 of file HyRRT.h.

◆ continuousSimulator

std::function<ompl::base::State *(const control::Control *control, ompl::base::State *x_cur, double tFlow, ompl::base::State *new_state)> ompl::control::HyRRT::continuousSimulator
Initial value:
=
[this](const control::Control *control, base::State *x_cur, double tFlow, base::State *new_state)
{
siC_->getStatePropagator()->propagate(x_cur, control, tFlow, new_state);
return new_state;
}
Definition of an abstract control.
Definition Control.h:48
control::SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition HyRRT.h:345
This namespace contains sampling based planning routines used by planning under differential constrai...
Definition Control.h:45

Simulates the dynamics of the multicopter when in flow regime, with no nonnegligble forces other than input acceleration.

Definition at line 224 of file HyRRT.h.

◆ continuousSimulator_

std::function<base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> ompl::control::HyRRT::continuousSimulator_
protected

Simulator for propagation under flow regime.

Parameters
inputThe input
curStateThe current state
tFlowMaxThe random maximum flow time
newStateThe newly propagated state
Returns
The newly propagated state

Definition at line 403 of file HyRRT.h.

◆ controlSampler_

control::DirectedControlSamplerPtr ompl::control::HyRRT::controlSampler_
protected

Control Sampler.

Definition at line 342 of file HyRRT.h.

◆ discreteSimulator_

std::function<base::State *(base::State *curState, const control::Control *u, base::State *newState)> ompl::control::HyRRT::discreteSimulator_
protected

Simulator for propagation under jump regime.

Parameters
curStateThe current state
uThe input
newStateThe newly propagated state
Returns
The newly propagated state

Definition at line 370 of file HyRRT.h.

◆ dist_

double ompl::control::HyRRT::dist_
protected

Minimum distance from goal to final vertex of generated trajectories.

Definition at line 416 of file HyRRT.h.

◆ distanceFunc_

std::function<double(base::State *state1, base::State *state2)> ompl::control::HyRRT::distanceFunc_
protected
Initial value:
=
[this](base::State *state1, base::State *state2) -> double { return si_->distance(state1, state2); }

Compute distance between states, default is Euclidean distance.

Parameters
state1The first state
state2The second state
Returns
The distance between the two states

Definition at line 353 of file HyRRT.h.

◆ flowSet_

std::function<bool(Motion *motion)> ompl::control::HyRRT::flowSet_
protected

Function that returns true if a motion intersects with the flow set, and false if not.

Parameters
motionThe motion to check
Returns
True if the state is in the flow set, false if not

Definition at line 384 of file HyRRT.h.

◆ flowStepDuration_

double ompl::control::HyRRT::flowStepDuration_
protected

The flow time for a given integration step, within a flow propagation step. Must be set by user.

Definition at line 360 of file HyRRT.h.

◆ jumpSet_

std::function<bool(Motion *motion)> ompl::control::HyRRT::jumpSet_
protected

Function that returns true if a motion intersects with the jump set, and false if not.

Parameters
motionThe motion to check
Returns
True if the state is in the jump set, false if not

Definition at line 377 of file HyRRT.h.

◆ lastGoalMotion_

Motion* ompl::control::HyRRT::lastGoalMotion_ {nullptr}
protected

The most recent goal motion. Used for PlannerData computation.

Definition at line 294 of file HyRRT.h.

◆ nn_

std::shared_ptr<NearestNeighbors<Motion *> > ompl::control::HyRRT::nn_
protected

A nearest-neighbors datastructure containing the tree of motions.

Definition at line 306 of file HyRRT.h.

◆ sampler_

base::StateSamplerPtr ompl::control::HyRRT::sampler_
protected

State sampler.

Definition at line 413 of file HyRRT.h.

◆ siC_

control::SpaceInformation* ompl::control::HyRRT::siC_
protected

The base::SpaceInformation cast as control::SpaceInformation, for convenience.

Definition at line 345 of file HyRRT.h.

◆ tM_

double ompl::control::HyRRT::tM_
protected

The maximum flow time for a given flow propagation step. Must be set by the user.

Definition at line 357 of file HyRRT.h.

◆ unsafeSet_

std::function<bool(Motion *motion)> ompl::control::HyRRT::unsafeSet_
protected

Function that returns true if a motion intersects with the unsafe set, and false if not.

Parameters
motionThe motion to check
Returns
True if the state is in the unsafe set, false if not

Definition at line 391 of file HyRRT.h.


The documentation for this class was generated from the following files: