Class HySST

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class HySST : public ompl::base::Planner

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]

Public Functions

HySST(const control::SpaceInformationPtr &si)

Constructor.

~HySST() override

Destructor.

virtual void setup() override

Set the problem instance to solve.

virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override

Main solve function.

Continue solving for some amount of time.

Parameters:

ptc – The condition to terminate solving.

Returns:

true if solution was found.

virtual void getPlannerData(base::PlannerData &data) const override

Get the PlannerData object associated with this planner.

Parameters:

data – the PlannerData object storing the edges and vertices of the solution

virtual void clear() override

Clear all allocated memory.

inline void setSelectionRadius(double selectionRadius)

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:

selectionRadius – The maximum distance from the random sampled vertex, for a vertex in the search tree to be considered

inline double getSelectionRadius() const

Get the selection radius the planner is using.

Returns:

The selection radius

inline void setPruningRadius(double pruningRadius)

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:

pruningRadius – The radius used to prune vertices in the search tree

inline double getPruningRadius() const

Get the pruning radius the planner is using.

Returns:

The pruning radius

template<template<typename T> class NN>
inline void setNearestNeighbors()

Set a different nearest neighbors datastructure.

inline void setTm(double tM)

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

Parameters:

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

inline void setFlowStepDuration(double duration)

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

Parameters:

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

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

Define the jump set.

Parameters:

jumpSet – the jump set associated with the hybrid system.

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

Define the flow set.

Parameters:

flowSet – the flow set associated with the hybrid system.

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

Define the unsafe set.

Parameters:

unsafeSet – the unsafe set associated with the hybrid system.

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

Define the distance measurement function.

Parameters:

function – the distance function associated with the motion planning problem.

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

Define the discrete dynamics simulator.

Parameters:

function – the discrete simulator associated with the hybrid system.

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

Define the continuous dynamics simulator.

Parameters:

function – the continuous simulator associated with the hybrid system.

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

Define the collision checker.

Parameters:

function – the collision checker associated with the state space. Default is a point-by-point collision checker.

inline void setBatchSize(int batchSize)

Set solution batch size.

Parameters:

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

inline void checkMandatoryParametersSet(void) const

Check if all required parameters have been set.

Public Members

std::function<ompl::base::State*(const control::Control *control, ompl::base::State *x_cur, double tFlow, ompl::base::State *new_state)> continuousSimulator = [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;}

Simulates the dynamics of the system.

Protected Functions

void initTree(void)

Runs the initial setup tasks for the tree.

void randomSample(Motion *randomMotion)

Sample the random motion.

Parameters:

randomMotion – The motion to be initialized

base::PlannerStatus constructSolution(Motion *lastMotion)

Construct the path, starting at the last edge.

Parameters:

lastMotion – The last motion in the solution

Returns:

the planner status (APPROXIMATE, EXACT, or UNKNOWN)

Motion *selectNode(Motion *sample)

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

Parameters:

sample – The random sampled vertex to find the closest witness to.

Witness *findClosestWitness(Motion *node)

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

Parameters:

node – The vertex to find the closest witness to.

std::vector<Motion*> extend(Motion *m)

Randomly propagate a new edge.

Parameters:

m – The motion to extend

void freeMemory()

Free the memory allocated by this planner.

Protected Attributes

Motion *lastGoalMotion_ = {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_ = [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 =ompl::base::HybridStateSpace::getStateTime(motion->solutionPair->back()) - flowStepDuration_;motion->solutionPair->resize(motion->solutionPair->size() - 1);return true;}return false;}

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.

Param motion:

The motion to check for collision

Param obstacleSet:

A function that returns true if the motion’s solution pair intersects with the obstacle set

Param ts:

The start time of the motion. Default is -1.0

Param tf:

The end time of the motion. Default is -1.0

Param newState:

The collision state (if a collision occurs)

Param collisionTime:

The time of collision (if a collision occurs). If no collision occurs, this value is -1.0

Return:

true if a collision occurs, false otherwise

control::DirectedControlSamplerPtr controlSampler_

Control Sampler.

control::SpaceInformation *siC_

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

std::function<double(base::State *state1, base::State *state2)> distanceFunc_ = [this](base::State *state1, base::State*state2) -> double{returnsi_->distance(state1, state2);}

Compute distance between states, default is Euclidean distance.

Param state1:

The first state

Param state2:

The second state

Return:

The distance between the two states

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.

Param curState:

The current state

Param u:

The input

Param newState:

The newly propagated state

Return:

The newly propagated state

std::function<bool(Motion *motion)> jumpSet_

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

Param motion:

The motion to check

Return:

True if the state is in the jump set, 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.

Param motion:

The motion to check

Return:

True if the state is in the flow set, 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.

Param motion:

The motion to check

Return:

True if the state is in the unsafe set, 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.

Param input:

The input

Param curState:

The current state

Param tFlowMax:

The random maximum flow time

Param newState:

The newly propagated state

Return:

The newly propagated state

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 Static Functions

static inline const ompl::control::Control *getFlowControl(const ompl::control::Control *control)
static inline const ompl::control::Control *getJumpControl(const ompl::control::Control *control)
class Motion

Representation of a motion.

This only contains pointers to parent motions as we

only need to go backwards in the tree.

Subclassed by ompl::control::HySST::Witness

Public Functions

Motion() = default

Default constructor.

inline Motion(const control::SpaceInformation *si)

Constructor that allocates memory for the state.

virtual ~Motion() = default

Destructor.

inline virtual base::State *getState() const

Get the state contained by the motion.

inline virtual Motion *getParent() const

Get the parent motion in the tree.

Public Members

base::Cost accCost_ = {0.}

The total cost accumulated from the root to this vertex.

base::State *state = {nullptr}

The state contained by the motion.

Motion *parent = {nullptr}

The parent motion in the exploration tree.

unsigned numChildren_ = {0}

Number of children. Starting with 0.

bool inactive_ = {false}

If inactive, this node is not considered for selection.

std::vector<base::State*> *solutionPair = {nullptr}

The integration steps defining the edge of the motion, between the parent and child vertices.

control::Control *control = {nullptr}

The inputs associated with the solution pair.

class Witness : public ompl::control::HySST::Motion

Representation of a witness vertex in the search tree.

Public Functions

Witness() = default

Default Constructor.

inline Witness(const control::SpaceInformation *si)

Constructor that allocates memory for the state.

inline virtual base::State *getState() const override

Get the state contained by the representative motion.

Returns:

The state contained by the representative motion

inline virtual Motion *getParent() const override

Get the state contained by the parent motion of the representative motion.

Returns:

The state contained by the parent motion of the representative motion

inline void linkRep(Motion *lRep)

Set the representative of the witness.

Parameters:

lRep – The representative motion

Public Members

Motion *rep_ = {nullptr}

The node in the tree that is within the pruning radius.