Loading...
Searching...
No Matches
HyRRT.h
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2025, University of Santa Cruz Hybrid Systems Laboratory
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the University of Santa Cruz nor the names of
18 * its contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Beverly Xu */
36
37#ifndef OMPL_CONTROL_PLANNERS_RRT_HYRRT_
38#define OMPL_CONTROL_PLANNERS_RRT_HYRRT_
39
40#include "ompl/base/spaces/RealVectorStateSpace.h"
41#include "ompl/control/ControlSpace.h"
42#include "ompl/control/spaces/RealVectorControlSpace.h"
43#include "ompl/datastructures/NearestNeighbors.h"
44#include "ompl/control/planners/PlannerIncludes.h"
45#include "ompl/control/Control.h"
46#include "ompl/base/spaces/HybridStateSpace.h"
47
48using namespace std;
49
50namespace ompl
51{
52 namespace control
53 {
74
76 class HyRRT : public base::Planner
77 {
78 public:
80 HyRRT(const control::SpaceInformationPtr &si);
81
83 ~HyRRT() override;
84
86 void clear() override;
87
89 void setup() override;
90
95 void getPlannerData(base::PlannerData &data) const override;
97
99 class Motion
100 {
101 public:
103 Motion() = default;
104
106 Motion(const control::SpaceInformation *si) : state(si->allocState()), control(si->allocControl())
107 {
108 }
109
111 ~Motion() = default;
112
115
117 Motion *parent{nullptr};
118
121 const base::State *root{nullptr};
122
125 std::vector<base::State *> *solutionPair{nullptr};
126
129 };
130
132 void freeMemory();
133
139 void setTm(double tM)
140 {
141 if (tM <= 0)
142 throw Exception("Maximum flow time per propagation step must be greater than 0");
144 {
145 if (tM < flowStepDuration_)
146 throw Exception(
147 "Maximum flow time per propagation step must be greater than or equal to the length of time for each flow "
148 "integration step (flowStepDuration_)");
149 }
150 tM_ = tM;
151 }
152
160 void setFlowStepDuration(double duration)
161 {
162 if (duration <= 0)
163 throw Exception("Flow step length must be greater than 0");
164 if (!tM_)
165 {
166 if (tM_ < duration)
167 throw Exception(
168 "Flow step length must be less than or equal to the maximum flow time per propagation step (Tm)");
169 }
170 flowStepDuration_ = duration;
171 }
172
177 void setJumpSet(std::function<bool(Motion *motion)> jumpSet)
178 {
179 jumpSet_ = jumpSet;
180 }
181
186 void setFlowSet(std::function<bool(Motion *motion)> flowSet)
187 {
188 flowSet_ = flowSet;
189 }
190
195 void setUnsafeSet(std::function<bool(Motion *motion)> unsafeSet)
196 {
197 unsafeSet_ = unsafeSet;
198 }
199
204 void setDistanceFunction(std::function<double(base::State *, base::State *)> function)
205 {
206 distanceFunc_ = function;
207 }
208
214 std::function<base::State *(base::State *curState, const control::Control *u, base::State *newState)>
215 function)
216 {
217 discreteSimulator_ = function;
218 }
219
222 std::function<ompl::base::State *(const control::Control *control, ompl::base::State *x_cur, double tFlow,
223 ompl::base::State *new_state)>
225 [this](const control::Control *control, base::State *x_cur, double tFlow, base::State *new_state)
226 {
227 siC_->getStatePropagator()->propagate(x_cur, control, tFlow, new_state);
228 return new_state;
229 };
230
236 void setCollisionChecker(std::function<bool(Motion *motion, std::function<bool(Motion *motion)> obstacleSet,
237 base::State *newState, double *collisionTime)>
238 function)
239 {
240 collisionChecker_ = function;
241 }
242
244 template <template <typename T> class NN>
246 {
247 if (nn_ && nn_->size() != 0)
248 OMPL_WARN("Calling setNearestNeighbors will clear all states.");
249 clear();
250 nn_ = std::make_shared<NN<Motion *>>();
251 setup();
252 }
253
256 {
258 throw Exception("Jump map not set");
260 throw Exception("Flow map not set");
261 if (!flowSet_)
262 throw Exception("Flow set not set");
263 if (!jumpSet_)
264 throw Exception("Jump set not set");
265 if (!unsafeSet_)
266 throw Exception("Unsafe set not set");
267 if (!tM_)
268 throw Exception("Max flow propagation time (Tm) no set");
269 }
270
271 protected:
276 void setContinuousSimulator(std::function<base::State *(const control::Control *u, base::State *curState,
277 double tFlowMax, base::State *newState)>
278 function)
279 {
280 continuousSimulator_ = function;
281 }
282
283 const static ompl::control::Control *getFlowControl(const ompl::control::Control *control)
284 {
286 }
287
288 const static ompl::control::Control *getJumpControl(const ompl::control::Control *control)
289 {
290 return control->as<CompoundControl>()->as<ompl::control::Control>(1);
291 }
292
295
297 void initTree(void);
298
303 void randomSample(Motion *randomMotion);
304
306 std::shared_ptr<NearestNeighbors<Motion *>> nn_;
307
312
325 std::function<bool(Motion *motion, std::function<bool(Motion *motion)> obstacleSet, base::State *newState,
326 double *collisionTime)>
327 collisionChecker_ = [this](Motion *motion, std::function<bool(Motion *motion)> obstacleSet,
328 base::State *newState, double *collisionTime) -> bool
329 {
330 if (obstacleSet(motion))
331 {
332 si_->copyState(newState, motion->solutionPair->back());
333 *collisionTime =
335 motion->solutionPair->resize(motion->solutionPair->size() - 1);
336 return true;
337 }
338 return false;
339 };
340
342 control::DirectedControlSamplerPtr controlSampler_;
343
346
353 std::function<double(base::State *state1, base::State *state2)> distanceFunc_ =
354 [this](base::State *state1, base::State *state2) -> double { return si_->distance(state1, state2); };
355
357 double tM_;
358
361
369 std::function<base::State *(base::State *curState, const control::Control *u, base::State *newState)>
371
377 std::function<bool(Motion *motion)> jumpSet_;
378
384 std::function<bool(Motion *motion)> flowSet_;
385
391 std::function<bool(Motion *motion)> unsafeSet_;
392
401 std::function<base::State *(const control::Control *u, base::State *curState, double tFlowMax,
402 base::State *newState)>
404
411
413 base::StateSamplerPtr sampler_;
414
416 double dist_;
417 };
418 } // namespace control
419} // namespace ompl
420
421#endif
The exception type for ompl.
Definition Exception.h:47
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...
Base class for a planner.
Definition Planner.h:216
T * as()
Cast this instance to a desired type.
Definition Planner.h:230
SpaceInformationPtr si_
The space information for which planning is done.
Definition Planner.h:401
Definition of an abstract state.
Definition State.h:50
Definition of a compound control.
Definition Control.h:85
Definition of an abstract control.
Definition Control.h:48
Representation of a motion in the search tree.
Definition HyRRT.h:100
~Motion()=default
Destructor.
Motion()=default
Default constructor.
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
base::State * state
The state contained by the motion.
Definition HyRRT.h:114
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
Motion * parent
The parent motion in the exploration tree.
Definition HyRRT.h:117
void clear() override
Clear all allocated memory.
Definition HyRRT.cpp:312
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 randomSample(Motion *randomMotion)
Sample the random motion.
Definition HyRRT.cpp:82
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
void setup() override
Set the problem instance to solve.
Definition HyRRT.cpp:322
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
base::StateSamplerPtr sampler_
State sampler.
Definition HyRRT.h:413
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
~HyRRT() override
Destructor.
Definition HyRRT.cpp:56
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
control::DirectedControlSamplerPtr controlSampler_
Control Sampler.
Definition HyRRT.h:342
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 initTree(void)
Runs the initial setup tasks for the tree.
Definition HyRRT.cpp:61
void freeMemory()
Free the memory allocated by this planner.
Definition HyRRT.cpp:332
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
HyRRT(const control::SpaceInformationPtr &si)
Constructor.
Definition HyRRT.cpp:50
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...
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains sampling based planning routines used by planning under differential constrai...
Definition Control.h:45
Main namespace. Contains everything in this library.
STL namespace.
A class to store the exit status of Planner::solve().