Loading...
Searching...
No Matches
PinballPlanning.cpp
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#include "ompl/control/planners/rrt/HyRRT.h"
38#include "ompl/base/StateSpace.h"
39#include "ompl/control/spaces/RealVectorControlSpace.h"
40#include "ompl/base/spaces/HybridStateSpace.h"
41#include "ompl/control/ODESolver.h"
42
43struct PinballSetup
44{
45 double paddleLength = 1;
46 double paddleWidth = 0.25;
47 std::vector<std::vector<double>> paddleCoords = {{1, -1}, {2.5, -4}, {1.5, -5}, {3, -7}, {1, -8}};
48};
49
51double distanceFunc(ompl::base::State *state1, ompl::base::State *state2)
52{
53 double dist = 0;
54 dist = hypot(state1->as<ompl::base::HybridStateSpace::StateType>()
56 ->values[0] -
59 ->values[0],
62 ->values[1] -
65 ->values[1]);
66 return fabs(dist);
67}
68
70bool inPaddle(ompl::control::HyRRT::Motion *motion, std::vector<double> paddleCoord)
71{
72 PinballSetup pinballSetup;
73
74 auto *motion_state =
75 motion->state->as<ompl::base::CompoundState>()->as<ompl::base::RealVectorStateSpace::StateType>(0);
76 double paddleX = paddleCoord[0];
77 double paddleY = paddleCoord[1];
78 double x1 = motion_state->values[0];
79 double x2 = motion_state->values[1];
80 double v1 = motion_state->values[2];
81 double v2 = motion_state->values[3];
82
83 bool inPaddle = false;
84
85 if ((x1 >= paddleX && x1 <= paddleX + pinballSetup.paddleLength) &&
86 (x2 >= paddleY && x2 <= paddleY + pinballSetup.paddleWidth / 2) && v2 < 0)
87 inPaddle = true; // In jump set if both velocity and position vectors are directed toward top of paddle
88 else if ((x1 >= paddleX && x1 <= paddleX + pinballSetup.paddleLength) &&
89 (x2 >= paddleY + pinballSetup.paddleWidth / 2 && x2 <= paddleY + pinballSetup.paddleWidth) && v2 > 0)
90 inPaddle = true; // In jump set if both velocity and position vectors are directed toward bottom of paddle
91 else if ((x1 >= paddleX && x1 <= paddleX + pinballSetup.paddleLength / 4) &&
92 (x2 >= paddleY && x2 <= paddleY + pinballSetup.paddleWidth) && v1 > 0)
93 inPaddle = true; // In jump set if both velocity and position vectors are directed toward left side of paddle
94 else if ((x1 >= paddleX + (3 / 4) * pinballSetup.paddleLength && x1 <= paddleX + pinballSetup.paddleLength) &&
95 (x2 >= paddleY && x2 <= paddleY + pinballSetup.paddleWidth) && v1 < 0)
96 inPaddle = true; // In jump set if both velocity and position vectors are directed toward left side of paddle
97
98 return inPaddle;
99}
100
102bool jumpSet(ompl::control::HyRRT::Motion *motion)
103{
104 PinballSetup pinballSetup;
105
106 auto *motion_state =
107 motion->state->as<ompl::base::CompoundState>()->as<ompl::base::RealVectorStateSpace::StateType>(0);
108 double x1 = motion_state->values[0];
109 double v1 = motion_state->values[2];
110
111 for (std::vector<double> paddleCoord : pinballSetup.paddleCoords) // If ball is in any of the paddles
112 {
113 if (inPaddle(motion, paddleCoord))
114 return true;
115 }
116
117 if ((x1 <= 0 && v1 < 0) || (x1 >= 5 && v1 > 0)) // If ball is in either side wall
118 return true;
119
120 return false;
121}
122
124bool flowSet(ompl::control::HyRRT::Motion *motion)
125{
126 return !jumpSet(motion);
127}
128
130bool unsafeSet(ompl::control::HyRRT::Motion *motion)
131{
132 auto *motion_state =
133 motion->state->as<ompl::base::CompoundState>()->as<ompl::base::RealVectorStateSpace::StateType>(0);
134 double x1 = motion_state->values[0];
135 double x2 = motion_state->values[1];
136
137 if (((x1 >= 0 && x1 < 1) || (x1 > 4 && x1 <= 5)) && x2 <= -10)
138 return true;
139 return false;
140}
141
144void flowODE(const ompl::control::ODESolver::StateType &x_cur, const ompl::control::Control *u,
146{
147 (void)u; // No control is applied when a state is in the flow set
148
149 // Retrieve the current orientation of the pinball.
150 const double v_1 = x_cur[2];
151 const double v_2 = x_cur[3];
152 const double a_1 = x_cur[4];
153 const double a_2 = x_cur[5];
154
155 // Ensure qdot is the same size as q. Zero out all values.
156 x_new.resize(x_cur.size(), 0);
157
158 x_new[0] = v_1;
159 x_new[1] = v_2;
160 x_new[2] = a_1;
161 x_new[3] = a_2;
162 x_new[4] = 0; // No change to acceleration
163 x_new[5] = 0; // No change to acceleration
164}
165
171ompl::base::State *discreteSimulator(ompl::base::State *x_cur, const ompl::control::Control *u,
172 ompl::base::State *new_state)
173{
174 // Retrieve control values.
176 const double u_x = control[0];
177
178 auto *state_values = x_cur->as<ompl::base::HybridStateSpace::StateType>()
179 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
180 ->values;
181 double x1 = state_values[0];
182 double x2 = state_values[1];
183 double v1 = state_values[2];
184 double v2 = state_values[3];
185 double a1 = state_values[4];
186 double a2 = state_values[5];
187
188 if ((x1 <= 0 && v1 < 0) || (x1 >= 5 && v1 > 0)) // If state is colliding with the wall
189 {
191 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
192 ->values[2] = -v1 * 0.8;
194 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
195 ->values[3] = v2;
196 }
197 else if (v2 < 0) // If state is colliding with the top of the paddle
198 {
200 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
201 ->values[2] = v1 + u_x;
203 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
204 ->values[3] = -v2 * 0.6;
205 }
206 else if (v2 > 0) // If state is colliding with the bottom of the paddle
207 {
209 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
210 ->values[2] = v1;
212 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
213 ->values[3] = -v2 * 0.6;
214 }
215 else // If state is colliding with the side of the paddle
216 {
218 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
219 ->values[2] = -(v1 * 0.6 + std::copysign(u_x, v1)); // Input is in the same direction as rebound
221 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
222 ->values[3] = v2;
223 }
224
225 // The position and acceleration doesn't change
227 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
228 ->values[0] = x1;
230 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
231 ->values[1] = x2;
233 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
234 ->values[4] = a1;
236 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
237 ->values[5] = a2;
238 return new_state;
239}
240
241// Define goal region [1, 4] x (-inf, -10] x ℝ⁴
242class EuclideanGoalRegion : public ompl::base::Goal
243{
244public:
245 EuclideanGoalRegion(const ompl::base::SpaceInformationPtr &si) : ompl::base::Goal(si)
246 {
247 }
248
249 virtual bool isSatisfied(const ompl::base::State *st, double *distance) const
250 {
251 // perform any operations and return a truth value
252 std::vector<double> goalRegion = {1, 4, -10}; // x-min, x-max, y
253 auto *values = st->as<ompl::base::CompoundState>()->as<ompl::base::RealVectorStateSpace::StateType>(0)->values;
254
255 if (values[0] > goalRegion[1])
256 *distance = hypot(values[1] + 10, values[0] - goalRegion[1]);
257 else if (values[0] < goalRegion[0])
258 *distance = hypot(values[1] + 10, values[0] - goalRegion[0]);
259 else
260 *distance = values[1] + 10;
261
262 return values[0] >= goalRegion[0] && values[0] <= goalRegion[1] && values[1] <= goalRegion[2];
263 }
264
265 virtual bool isSatisfied(const ompl::base::State *st) const
266 {
267 double distance = -1.0;
268 return isSatisfied(st, &distance);
269 }
270};
271
272int main()
273{
274 // Set the bounds of space
276 statespace->addDimension(0, 5);
277 statespace->addDimension(-10, 0);
278 statespace->addDimension(-10, 10);
279 statespace->addDimension(-10, 10);
280 statespace->addDimension(-10, 10);
281 statespace->addDimension(-10, 10);
282 ompl::base::StateSpacePtr stateSpacePtr(statespace);
283
284 ompl::base::HybridStateSpace *hybridSpace = new ompl::base::HybridStateSpace(stateSpacePtr);
285 ompl::base::StateSpacePtr hybridSpacePtr(hybridSpace);
286
287 // Define control space
288 ompl::control::RealVectorControlSpace *flowControlSpace =
289 new ompl::control::RealVectorControlSpace(hybridSpacePtr, 1);
290 ompl::control::RealVectorControlSpace *jumpControlSpace =
291 new ompl::control::RealVectorControlSpace(hybridSpacePtr, 1);
292
293 ompl::base::RealVectorBounds flowBounds(1);
294 flowBounds.setLow(0, 0);
295 flowBounds.setHigh(0, 0);
296 flowControlSpace->setBounds(flowBounds);
297
298 ompl::base::RealVectorBounds jumpBounds(1);
299 jumpBounds.setLow(0, -4);
300 jumpBounds.setHigh(0, 4);
301 jumpControlSpace->setBounds(jumpBounds);
302
303 ompl::control::RealVectorControlUniformSampler flowControlSampler(flowControlSpace);
304 flowControlSpace->setControlSamplerAllocator(
305 [](const ompl::control::ControlSpace *space) -> ompl::control::ControlSamplerPtr
306 { return std::make_shared<ompl::control::RealVectorControlUniformSampler>(space); });
307
309 jumpControlSpace); // Doesn't do anything because the bounds for jump input are just [0, 0], but here for
310 // demonstration
311 jumpControlSpace->setControlSamplerAllocator(
312 [](const ompl::control::ControlSpace *space) -> ompl::control::ControlSamplerPtr
313 { return std::make_shared<ompl::control::RealVectorControlUniformSampler>(space); });
314
315 ompl::control::ControlSpacePtr flowControlSpacePtr(flowControlSpace);
316 ompl::control::ControlSpacePtr jumpControlSpacePtr(jumpControlSpace);
317
319 controlSpace->addSubspace(flowControlSpacePtr);
320 controlSpace->addSubspace(jumpControlSpacePtr);
321
322 ompl::control::ControlSpacePtr controlSpacePtr(controlSpace);
323
324 // Construct a space information instance for this state space
325 ompl::control::SpaceInformationPtr si(new ompl::control::SpaceInformation(hybridSpacePtr, controlSpacePtr));
326 ompl::control::ODESolverPtr odeSolver(new ompl::control::ODEBasicSolver<>(si, &flowODE));
327
328 si->setStatePropagator(ompl::control::ODESolver::getStatePropagator(odeSolver));
329 si->setPropagationStepSize(0.01);
330 si->setup();
331
332 // Create a problem instance
333 ompl::base::ProblemDefinitionPtr pdef(new ompl::base::ProblemDefinition(si));
334
335 std::vector<ompl::base::ScopedState<>> startStates;
336 std::vector<double> startXs = {0.5, 1, 2, 3.5, 4, 4.5};
337
338 for (std::size_t i = 0; i < startXs.size(); i++)
339 {
340 startStates.push_back(ompl::base::ScopedState<>(hybridSpacePtr));
341 startStates.back()
343 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
344 ->values[0] = startXs[i];
345 startStates.back()
347 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
348 ->values[1] = 0;
349 startStates.back()
351 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
352 ->values[2] = 0;
353 startStates.back()
355 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
356 ->values[3] = 0;
357 startStates.back()
359 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
360 ->values[4] = 0;
361 startStates.back()
363 ->as<ompl::base::RealVectorStateSpace::StateType>(0)
364 ->values[5] = -9.81;
365 pdef->addStartState(startStates.back());
366 }
367
368 // Set goal state to be on floor with a zero velocity, and tolerance of 0.1
369 std::shared_ptr<EuclideanGoalRegion> goal = std::make_shared<EuclideanGoalRegion>(si);
370
371 // Set the goal region
372 pdef->setGoal(goal);
373
374 ompl::control::HyRRT cHyRRT(si);
375
376 // Set the problem instance for our planner to solve
377 cHyRRT.setProblemDefinition(pdef);
378 cHyRRT.setup();
379
380 // Set parameters
381 cHyRRT.setDiscreteSimulator(discreteSimulator);
382 cHyRRT.setDistanceFunction(distanceFunc);
383 cHyRRT.setFlowSet(flowSet);
384 cHyRRT.setJumpSet(jumpSet);
385 cHyRRT.setTm(0.5);
386 cHyRRT.setFlowStepDuration(0.01);
387 cHyRRT.setUnsafeSet(unsafeSet);
388
389 // attempt to solve the planning problem within 15 seconds
392 double planTime = ompl::time::seconds(ompl::time::now() - t0);
393
394 if (solved) // If either approximate or exact solution has beenf ound
395 OMPL_INFORM("Solution found in %f seconds", planTime);
396 OMPL_INFORM("Solution status: %s", solved.asString().c_str());
397
398 // print path
399 pdef->getSolutionPath()->as<ompl::control::PathControl>()->printAsMatrix(std::cout);
400}
Definition of a compound state.
Definition State.h:87
Abstract definition of goals.
Definition Goal.h:63
T * as()
Cast this instance to a desired type.
Definition Goal.h:77
A state space consisting of a space and a time component.
Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...
The lower and upper bounds for an Rn space.
double * values
The value of the actual vector in Rn.
A state space representing Rn. The distance function is the L2 norm.
void addDimension(double minBound=0.0, double maxBound=0.0)
Increase the dimensionality of the state space by 1. Optionally, bounds can be specified for this add...
Definition of a scoped state.
Definition ScopedState.h:57
ompl::base::State StateType
Define the type of state allocated by this space.
Definition StateSpace.h:78
Definition of an abstract state.
Definition State.h:50
const T * as() const
Cast this instance to a desired type.
Definition State.h:66
A control space to allow the composition of control spaces.
virtual void addSubspace(const ControlSpacePtr &component)
Adds a control space as a component of the compound control space.
A control space representing the space of applicable controls.
void setControlSamplerAllocator(const ControlSamplerAllocator &csa)
Set the sampler allocator to use.
Definition of an abstract control.
Definition Control.h:48
const T * as() const
Cast this instance to a desired type.
Definition Control.h:64
Representation of a motion in the search tree.
Definition HyRRT.h:100
base::State * state
The state contained by the motion.
Definition HyRRT.h:114
Hybrid Rapidly-exploring Random Trees.
Definition HyRRT.h:77
Basic solver for ordinary differential equations of the type q' = f(q, u), where q is the current sta...
Definition ODESolver.h:200
std::vector< double > StateType
Portable data type for the state values.
Definition ODESolver.h:77
static StatePropagatorPtr getStatePropagator(ODESolverPtr solver, const PostPropagationEvent &postEvent=nullptr)
Retrieve a StatePropagator object that solves a system of ordinary differential equations defined by ...
Definition ODESolver.h:127
Definition of a control path.
Definition PathControl.h:61
A control space representing Rn.
void setBounds(const base::RealVectorBounds &bounds)
Set the bounds (min max values for each dimension) for the control.
Uniform sampler for the Rn state space.
Space information containing necessary information for planning with controls. setup() needs to be ca...
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition Console.h:68
PlannerTerminationCondition timedPlannerTerminationCondition(double duration)
Return a termination condition that will become true duration seconds in the future (wall-time).
This namespace contains sampling based planning routines used by planning under differential constrai...
Definition Control.h:45
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition Time.h:52
point now()
Get the current time point.
Definition Time.h:58
duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition Time.h:64
A class to store the exit status of Planner::solve().
std::string asString() const
Return a string representation.