Loading...
Searching...
No Matches
HyRRT.h
106 Motion(const control::SpaceInformation *si) : state(si->allocState()), control(si->allocControl())
214 std::function<base::State *(base::State *curState, const control::Control *u, base::State *newState)>
222 std::function<ompl::base::State *(const control::Control *control, ompl::base::State *x_cur, double tFlow,
225 [this](const control::Control *control, base::State *x_cur, double tFlow, base::State *new_state)
236 void setCollisionChecker(std::function<bool(Motion *motion, std::function<bool(Motion *motion)> obstacleSet,
276 void setContinuousSimulator(std::function<base::State *(const control::Control *u, base::State *curState,
325 std::function<bool(Motion *motion, std::function<bool(Motion *motion)> obstacleSet, base::State *newState,
354 [this](base::State *state1, base::State *state2) -> double { return si_->distance(state1, state2); };
369 std::function<base::State *(base::State *curState, const control::Control *u, base::State *newState)>
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
Definition HybridStateSpace.cpp:98
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition PlannerData.h:175
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Definition PlannerTerminationCondition.h:64
Motion(const control::SpaceInformation *si)
Constructor that allocates memory for the state.
Definition HyRRT.h:106
const base::State * root
Pointer to the root of the tree this motion is contained in.
Definition HyRRT.h:121
std::vector< base::State * > * solutionPair
The integration steps defining the solution pair of the motion, between the parent and child vertices...
Definition HyRRT.h:125
void setUnsafeSet(std::function< bool(Motion *motion)> unsafeSet)
Define the unsafe set.
Definition HyRRT.h:195
std::function< base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> continuousSimulator_
Simulator for propagation under flow regime.
Definition HyRRT.h:403
base::PlannerStatus constructSolution(Motion *lastMotion)
Construct the path, starting at the last edge.
Definition HyRRT.cpp:254
std::function< double(base::State *state1, base::State *state2)> distanceFunc_
Compute distance between states, default is Euclidean distance.
Definition HyRRT.h:353
void checkMandatoryParametersSet(void) const
Check if all required parameters have been set.
Definition HyRRT.h:255
void setDiscreteSimulator(std::function< base::State *(base::State *curState, const control::Control *u, base::State *newState)> function)
Define the discrete dynamics simulator.
Definition HyRRT.h:213
Motion * lastGoalMotion_
The most recent goal motion. Used for PlannerData computation.
Definition HyRRT.h:294
void setFlowSet(std::function< bool(Motion *motion)> flowSet)
Define the flow set.
Definition HyRRT.h:186
base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override
Function that can solve the motion planning problem. This function can be called multiple times on th...
Definition HyRRT.cpp:87
void setDistanceFunction(std::function< double(base::State *, base::State *)> function)
Define the distance measurement function.
Definition HyRRT.h:204
std::function< bool(Motion *motion)> jumpSet_
Function that returns true if a motion intersects with the jump set, and false if not.
Definition HyRRT.h:377
std::function< base::State *(base::State *curState, const control::Control *u, base::State *newState)> discreteSimulator_
Simulator for propagation under jump regime.
Definition HyRRT.h:370
void setCollisionChecker(std::function< bool(Motion *motion, std::function< bool(Motion *motion)> obstacleSet, base::State *newState, double *collisionTime)> function)
Define the collision checker.
Definition HyRRT.h:236
std::function< bool(Motion *motion)> flowSet_
Function that returns true if a motion intersects with the flow set, and false if not.
Definition HyRRT.h:384
std::shared_ptr< NearestNeighbors< Motion * > > nn_
A nearest-neighbors datastructure containing the tree of motions.
Definition HyRRT.h:306
void setTm(double tM)
Set the maximum time allocated to a full continuous simulator step.
Definition HyRRT.h:139
void setJumpSet(std::function< bool(Motion *motion)> jumpSet)
Define the jump set.
Definition HyRRT.h:177
control::SpaceInformation * siC_
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition HyRRT.h:345
void getPlannerData(base::PlannerData &data) const override
Get the PlannerData object associated with this planner.
Definition HyRRT.cpp:354
void setContinuousSimulator(std::function< base::State *(const control::Control *u, base::State *curState, double tFlowMax, base::State *newState)> function)
Define the continuous dynamics simulator.
Definition HyRRT.h:276
void setFlowStepDuration(double duration)
Set the time allocated to a single continuous simulator call, within the full period of a continuous ...
Definition HyRRT.h:160
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...
Definition HyRRT.h:224
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.
Definition HyRRT.h:327
double flowStepDuration_
The flow time for a given integration step, within a flow propagation step. Must be set by user.
Definition HyRRT.h:360
std::function< bool(Motion *motion)> unsafeSet_
Function that returns true if a motion intersects with the unsafe set, and false if not.
Definition HyRRT.h:391
void setNearestNeighbors(void)
Set a different nearest neighbors datastructure.
Definition HyRRT.h:245
double tM_
The maximum flow time for a given flow propagation step. Must be set by the user.
Definition HyRRT.h:357
double dist_
Minimum distance from goal to final vertex of generated trajectories.
Definition HyRRT.h:416
Space information containing necessary information for planning with controls. setup() needs to be ca...
Definition SpaceInformation.h:71
This namespace contains sampling based planning routines used by planning under differential constrai...
Definition Control.h:45
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66
STL namespace.
A class to store the exit status of Planner::solve().
Definition PlannerStatus.h:49