Loading...
Searching...
No Matches

#include <ompl/control/planners/sst/HySST.h>

Inheritance diagram for ompl::control::HySST:

Classes

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

Public Member Functions

 HySST (const control::SpaceInformationPtr &si)
 Constructor.
 ~HySST () override
 Destructor.
void setup () override
 Set the problem instance to solve.
base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc) override
 Main solve function.
void getPlannerData (base::PlannerData &data) const override
 Get the PlannerData object associated with this planner.
void clear () override
 Clear all allocated memory.
void setSelectionRadius (double selectionRadius)
 Set the radius for selecting nodes relative to random sample.
double getSelectionRadius () const
 Get the selection radius the planner is using.
void setPruningRadius (double pruningRadius)
 Set the radius for pruning nodes.
double getPruningRadius () const
 Get the pruning radius the planner is using.
template<template< typename T > class NN>
void setNearestNeighbors ()
 Set a different nearest neighbors datastructure.
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 *)> jumpSet)
 Define the jump set.
void setFlowSet (std::function< bool(Motion *)> flowSet)
 Define the flow set.
void setUnsafeSet (std::function< bool(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 setContinuousSimulator (std::function< base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> function)
 Define the continuous 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.
void setBatchSize (int batchSize)
 Set solution batch size.
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 system.

Protected Member Functions

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.
MotionselectNode (Motion *sample)
 Finds the best node in the tree withing the selection radius around a random sample.
WitnessfindClosestWitness (Motion *node)
 Find the closest witness node to a newly generated potential node.
std::vector< Motion * > extend (Motion *m)
 Randomly propagate a new edge.
void freeMemory ()
 Free the memory allocated by this planner.
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_ {-1.}
 The maximum flow time for a given flow propagation step. Must be set by the user.
double minStepLength = 1e-06
 The minimum step length for a given flow propagation step. Default value is 1e-6.
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.
base::OptimizationObjectivePtr opt_
 The optimization objective. Default is a shortest path objective.
std::function< base::Cost(Motion *motion)> costFunc_
 Calculate the cost of a motion. Default is using optimization objective.
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.
std::shared_ptr< NearestNeighbors< Motion * > > witnesses_
 A nearest-neighbors datastructure containing the tree of witness motions.
double selectionRadius_ {-1.}
 The radius for determining the node selected for extension. Delta_s.
double pruningRadius_ {-1.}
 The radius for determining the size of the pruning region. Delta_bn.
RNG rng_
 The random number generator.
double dist_
 Minimum distance from goal to final vertex of generated trajectories.
std::vector< Motion * > prevSolution_
 The best solution (with best cost) we have found so far.
base::Cost prevSolutionCost_ {std::numeric_limits<double>::quiet_NaN()}
 The best solution cost we have found so far.
int batchSize_ {1}
 The number of solutions allowed until the most optimal solution is returned.
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 Stable-sparse RRT (HySST) is an asymptotically near-optimal incremental
sampling-based motion planning algorithm. It is recommended for geometric problems to use an alternative method that makes use of a steering function. Using HySST for geometric problems does not take advantage of this function.
External documentation
N. Wang and R. G. Sanfelice, "HySST: An Asymptotically Near-Optimal Motion Planning Algorithm for Hybrid Systems." [PDF]

Definition at line 63 of file HySST.h.

Constructor & Destructor Documentation

◆ HySST()

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

Constructor.

Definition at line 52 of file HySST.cpp.

◆ ~HySST()

ompl::control::HySST::~HySST ( )
override

Destructor.

Definition at line 61 of file HySST.cpp.

Member Function Documentation

◆ checkMandatoryParametersSet()

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

Check if all required parameters have been set.

Definition at line 339 of file HySST.h.

◆ clear()

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

Clear all allocated memory.

Reimplemented from ompl::base::Planner.

Definition at line 104 of file HySST.cpp.

◆ constructSolution()

ompl::base::PlannerStatus ompl::control::HySST::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 495 of file HySST.cpp.

◆ extend()

std::vector< ompl::control::HySST::Motion * > ompl::control::HySST::extend ( Motion * m)
protected

Randomly propagate a new edge.

Parameters
mThe motion to extend

Definition at line 195 of file HySST.cpp.

◆ findClosestWitness()

ompl::control::HySST::Witness * ompl::control::HySST::findClosestWitness ( Motion * node)
protected

Find the closest witness node to a newly generated potential node.

Parameters
nodeThe vertex to find the closest witness to.

Definition at line 177 of file HySST.cpp.

◆ freeMemory()

void ompl::control::HySST::freeMemory ( )
protected

Free the memory allocated by this planner.

Definition at line 117 of file HySST.cpp.

◆ getFlowControl()

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

Definition at line 360 of file HySST.h.

◆ getJumpControl()

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

Definition at line 365 of file HySST.h.

◆ getPlannerData()

void ompl::control::HySST::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 562 of file HySST.cpp.

◆ getPruningRadius()

double ompl::control::HySST::getPruningRadius ( ) const
inline

Get the pruning radius the planner is using.

Returns
The pruning radius

Definition at line 191 of file HySST.h.

◆ getSelectionRadius()

double ompl::control::HySST::getSelectionRadius ( ) const
inline

Get the selection radius the planner is using.

Returns
The selection radius

Definition at line 164 of file HySST.h.

◆ randomSample()

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

Sample the random motion.

Parameters
randomMotionThe motion to be initialized

Definition at line 318 of file HySST.cpp.

◆ selectNode()

ompl::control::HySST::Motion * ompl::control::HySST::selectNode ( Motion * sample)
protected

Finds the best node in the tree withing the selection radius around a random sample.

Parameters
sampleThe random sampled vertex to find the closest witness to.

Definition at line 144 of file HySST.cpp.

◆ setBatchSize()

void ompl::control::HySST::setBatchSize ( int batchSize)
inline

Set solution batch size.

Parameters
batchSizethe number of solutions to be generated by the planner until the one with the best cost is returned.

Definition at line 332 of file HySST.h.

◆ setCollisionChecker()

void ompl::control::HySST::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 320 of file HySST.h.

◆ setContinuousSimulator()

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

Define the continuous dynamics simulator.

Parameters
functionthe continuous simulator associated with the hybrid system.

Definition at line 298 of file HySST.h.

◆ setDiscreteSimulator()

void ompl::control::HySST::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 287 of file HySST.h.

◆ setDistanceFunction()

void ompl::control::HySST::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 278 of file HySST.h.

◆ setFlowSet()

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

Define the flow set.

Parameters
flowSetthe flow set associated with the hybrid system.

Definition at line 260 of file HySST.h.

◆ setFlowStepDuration()

void ompl::control::HySST::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 234 of file HySST.h.

◆ setJumpSet()

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

Define the jump set.

Parameters
jumpSetthe jump set associated with the hybrid system.

Definition at line 251 of file HySST.h.

◆ setNearestNeighbors()

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

Set a different nearest neighbors datastructure.

Definition at line 198 of file HySST.h.

◆ setPruningRadius()

void ompl::control::HySST::setPruningRadius ( double pruningRadius)
inline

Set the radius for pruning nodes.

This is the radius used to surround nodes in the witness set.
Within this radius around a state in the witness set, only one active tree node can exist. This limits the size of the tree and forces computation to focus on low path costs nodes. If this value is too large, narrow passages will be impossible to traverse. In addition, children nodes may be removed if they are not at least this distance away from their parent nodes.
Parameters
pruningRadiusThe radius used to prune vertices in the search tree

Definition at line 180 of file HySST.h.

◆ setSelectionRadius()

void ompl::control::HySST::setSelectionRadius ( double selectionRadius)
inline

Set the radius for selecting nodes relative to random sample.

This radius is used to mimic behavior of RRT* in that it promotes
extending from nodes with good path cost from the root of the tree. Making this radius larger will provide higher quality paths, but has two major drawbacks; exploration will occur much more slowly and exploration around the boundary of the state space may become impossible.
Parameters
selectionRadiusThe maximum distance from the random sampled vertex, for a vertex in the search tree to be considered

Definition at line 153 of file HySST.h.

◆ setTm()

void ompl::control::HySST::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 213 of file HySST.h.

◆ setUnsafeSet()

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

Define the unsafe set.

Parameters
unsafeSetthe unsafe set associated with the hybrid system.

Definition at line 269 of file HySST.h.

◆ setup()

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

Set the problem instance to solve.

Reimplemented from ompl::base::Planner.

Definition at line 65 of file HySST.cpp.

◆ solve()

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

Main solve function.

Continue solving for some amount of time.
Parameters
ptcThe condition to terminate solving.
Returns
true if solution was found.

Implements ompl::base::Planner.

Definition at line 323 of file HySST.cpp.

Member Data Documentation

◆ batchSize_

int ompl::control::HySST::batchSize_ {1}
protected

The number of solutions allowed until the most optimal solution is returned.

Definition at line 587 of file HySST.h.

◆ collisionChecker_

std::function<bool(Motion *motion, std::function<bool(Motion *motion)> obstacleSet, base::State *newState, double *collisionTime)> ompl::control::HySST::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 cHySST 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 447 of file HySST.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::HySST::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 system.

Definition at line 308 of file HySST.h.

◆ continuousSimulator_

std::function<base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> ompl::control::HySST::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 532 of file HySST.h.

◆ controlSampler_

control::DirectedControlSamplerPtr ompl::control::HySST::controlSampler_
protected

Control Sampler.

Definition at line 462 of file HySST.h.

◆ costFunc_

std::function<base::Cost(Motion *motion)> ompl::control::HySST::costFunc_
protected

Calculate the cost of a motion. Default is using optimization objective.

Definition at line 520 of file HySST.h.

◆ discreteSimulator_

std::function<base::State *(base::State *curState, const control::Control *u, base::State *newState)> ompl::control::HySST::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 493 of file HySST.h.

◆ dist_

double ompl::control::HySST::dist_
protected

Minimum distance from goal to final vertex of generated trajectories.

Definition at line 578 of file HySST.h.

◆ distanceFunc_

std::function<double(base::State *state1, base::State *state2)> ompl::control::HySST::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 473 of file HySST.h.

◆ flowSet_

std::function<bool(Motion *motion)> ompl::control::HySST::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 507 of file HySST.h.

◆ flowStepDuration_

double ompl::control::HySST::flowStepDuration_
protected

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

Definition at line 483 of file HySST.h.

◆ jumpSet_

std::function<bool(Motion *motion)> ompl::control::HySST::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 500 of file HySST.h.

◆ lastGoalMotion_

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

The most recent goal motion. Used for PlannerData computation.

Definition at line 414 of file HySST.h.

◆ minStepLength

double ompl::control::HySST::minStepLength = 1e-06
protected

The minimum step length for a given flow propagation step. Default value is 1e-6.

Definition at line 480 of file HySST.h.

◆ nn_

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

A nearest-neighbors datastructure containing the tree of motions.

Definition at line 426 of file HySST.h.

◆ opt_

base::OptimizationObjectivePtr ompl::control::HySST::opt_
protected

The optimization objective. Default is a shortest path objective.

Definition at line 517 of file HySST.h.

◆ prevSolution_

std::vector<Motion *> ompl::control::HySST::prevSolution_
protected

The best solution (with best cost) we have found so far.

Definition at line 581 of file HySST.h.

◆ prevSolutionCost_

base::Cost ompl::control::HySST::prevSolutionCost_ {std::numeric_limits<double>::quiet_NaN()}
protected

The best solution cost we have found so far.

Definition at line 584 of file HySST.h.

◆ pruningRadius_

double ompl::control::HySST::pruningRadius_ {-1.}
protected

The radius for determining the size of the pruning region. Delta_bn.

Definition at line 572 of file HySST.h.

◆ rng_

RNG ompl::control::HySST::rng_
protected

The random number generator.

Definition at line 575 of file HySST.h.

◆ sampler_

base::StateSamplerPtr ompl::control::HySST::sampler_
protected

State sampler.

Definition at line 563 of file HySST.h.

◆ selectionRadius_

double ompl::control::HySST::selectionRadius_ {-1.}
protected

The radius for determining the node selected for extension. Delta_s.

Definition at line 569 of file HySST.h.

◆ siC_

control::SpaceInformation* ompl::control::HySST::siC_
protected

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

Definition at line 465 of file HySST.h.

◆ tM_

double ompl::control::HySST::tM_ {-1.}
protected

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

Definition at line 477 of file HySST.h.

◆ unsafeSet_

std::function<bool(Motion *motion)> ompl::control::HySST::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 514 of file HySST.h.

◆ witnesses_

std::shared_ptr<NearestNeighbors<Motion *> > ompl::control::HySST::witnesses_
protected

A nearest-neighbors datastructure containing the tree of witness motions.

Definition at line 566 of file HySST.h.


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