|
| | 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.
|
|
| 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 SpaceInformationPtr & | getSpaceInformation () const |
| | Get the space information this planner is using.
|
| const ProblemDefinitionPtr & | getProblemDefinition () const |
| | Get the problem definition the planner is trying to solve.
|
| ProblemDefinitionPtr & | getProblemDefinition () |
| | Get the problem definition the planner is trying to solve.
|
| const PlannerInputStates & | getPlannerInputStates () 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 PlannerSpecs & | getSpecs () 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.
|
| ParamSet & | params () |
| | Get the parameters for this planner.
|
| const ParamSet & | params () const |
| | Get the parameters for this planner.
|
| const PlannerProgressProperties & | getPlannerProgressProperties () 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.
|
|
| 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.
|
| 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.
|
|
| 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_ |
| | Collision checker. Default is point-by-point collision checking using the jump set.
|
| 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_ |
| | 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.
|
| 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.
|
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:
- Initialize the tree with a start state.
- 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.
- 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.