Loading...
Searching...
No Matches
RigidBodyPlanningWithODESolverAndControls.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Rice University
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 Rice University nor the names of its
18 * 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: Ryan Luna */
36
37#include <ompl/control/SpaceInformation.h>
38#include <ompl/base/spaces/SE2StateSpace.h>
39#include <ompl/control/ODESolver.h>
40#include <ompl/control/spaces/RealVectorControlSpace.h>
41#include <ompl/control/SimpleSetup.h>
42#include <ompl/config.h>
43#include <iostream>
44#include <valarray>
45#include <limits>
46
47namespace ob = ompl::base;
48namespace oc = ompl::control;
49
50// Kinematic car model object definition. This class does NOT use ODESolver to propagate the system.
51class KinematicCarModel : public oc::StatePropagator
52{
53public:
54 KinematicCarModel(const oc::SpaceInformationPtr &si) : oc::StatePropagator(si)
55 {
56 space_ = si->getStateSpace();
57 carLength_ = 0.2;
58 timeStep_ = 0.01;
59 }
60
61 void propagate(const ob::State *state, const oc::Control *control, const double duration,
62 ob::State *result) const override
63 {
64 EulerIntegration(state, control, duration, result);
65 }
66
67protected:
68 // Explicit Euler Method for numerical integration.
69 void EulerIntegration(const ob::State *start, const oc::Control *control, const double duration,
70 ob::State *result) const
71 {
72 double t = timeStep_;
73 std::valarray<double> dstate;
74 space_->copyState(result, start);
75 while (t < duration + std::numeric_limits<double>::epsilon())
76 {
77 ode(result, control, dstate);
78 update(result, timeStep_ * dstate);
79 t += timeStep_;
80 }
81 if (t + std::numeric_limits<double>::epsilon() > duration)
82 {
83 ode(result, control, dstate);
84 update(result, (t - duration) * dstate);
85 }
86 }
87
89 void ode(const ob::State *state, const oc::Control *control, std::valarray<double> &dstate) const
90 {
91 const double *u = control->as<oc::RealVectorControlSpace::ControlType>()->values;
92 const double theta = state->as<ob::SE2StateSpace::StateType>()->getYaw();
93
94 dstate.resize(3);
95 dstate[0] = u[0] * cos(theta);
96 dstate[1] = u[0] * sin(theta);
97 dstate[2] = u[0] * tan(u[1]) / carLength_;
98 }
99
101 void update(ob::State *state, const std::valarray<double> &dstate) const
102 {
104 s.setX(s.getX() + dstate[0]);
105 s.setY(s.getY() + dstate[1]);
106 s.setYaw(s.getYaw() + dstate[2]);
107 space_->enforceBounds(state);
108 }
109
110 ob::StateSpacePtr space_;
111 double carLength_;
112 double timeStep_;
113};
114
115// Definition of the ODE for the kinematic car.
116// This method is analogous to the above KinematicCarModel::ode function.
117void KinematicCarODE(const oc::ODESolver::StateType &q, const oc::Control *control, oc::ODESolver::StateType &qdot)
118{
119 const double *u = control->as<oc::RealVectorControlSpace::ControlType>()->values;
120 const double theta = q[2];
121 double carLength = 0.2;
122
123 // Zero out qdot
124 qdot.resize(q.size(), 0);
125
126 qdot[0] = u[0] * cos(theta);
127 qdot[1] = u[0] * sin(theta);
128 qdot[2] = u[0] * tan(u[1]) / carLength;
129}
130
131// This is a callback method invoked after numerical integration.
132void KinematicCarPostIntegration(const ob::State * /*state*/, const oc::Control * /*control*/,
133 const double /*duration*/, ob::State *result)
134{
135 // Normalize orientation between 0 and 2*pi
138}
139
140bool isStateValid(const oc::SpaceInformation *si, const ob::State *state)
141{
142 // ob::ScopedState<ob::SE2StateSpace>
144 const auto *se2state = state->as<ob::SE2StateSpace::StateType>();
145
147 const auto *pos = se2state->as<ob::RealVectorStateSpace::StateType>(0);
148
150 const auto *rot = se2state->as<ob::SO2StateSpace::StateType>(1);
151
153
154 // return a value that is always true but uses the two variables we define, so we avoid compiler warnings
155 return si->satisfiesBounds(state) && (const void *)rot != (const void *)pos;
156}
157
159class DemoControlSpace : public oc::RealVectorControlSpace
160{
161public:
162 DemoControlSpace(const ob::StateSpacePtr &stateSpace) : oc::RealVectorControlSpace(stateSpace, 2)
163 {
164 }
165};
167
168void planWithSimpleSetup()
169{
171 auto space(std::make_shared<ob::SE2StateSpace>());
172
174 ob::RealVectorBounds bounds(2);
175 bounds.setLow(-1);
176 bounds.setHigh(1);
177
178 space->setBounds(bounds);
179
180 // create a control space
181 auto cspace(std::make_shared<DemoControlSpace>(space));
182
183 // set the bounds for the control space
184 ob::RealVectorBounds cbounds(2);
185 cbounds.setLow(-0.3);
186 cbounds.setHigh(0.3);
187
188 cspace->setBounds(cbounds);
189
190 // define a simple setup class
191 oc::SimpleSetup ss(cspace);
192
193 // set state validity checking for this space
194 oc::SpaceInformation *si = ss.getSpaceInformation().get();
195 ss.setStateValidityChecker([si](const ob::State *state) { return isStateValid(si, state); });
196
197 // Setting the propagation routine for this space:
198 // KinematicCarModel does NOT use ODESolver
199 // ss.setStatePropagator(std::make_shared<KinematicCarModel>(ss.getSpaceInformation()));
200
201 // Use the ODESolver to propagate the system. Call KinematicCarPostIntegration
202 // when integration has finished to normalize the orientation values.
203 auto odeSolver(std::make_shared<oc::ODEBasicSolver<>>(ss.getSpaceInformation(), &KinematicCarODE));
204 ss.setStatePropagator(oc::ODESolver::getStatePropagator(odeSolver, &KinematicCarPostIntegration));
205
208 start->setX(-0.5);
209 start->setY(0.0);
210 start->setYaw(0.0);
211
214 goal->setX(0.0);
215 goal->setY(0.5);
216 goal->setYaw(0.0);
217
219 ss.setStartAndGoalStates(start, goal, 0.05);
220
222 ss.setup();
223
225 ob::PlannerStatus solved = ss.solve(10.0);
226
227 if (solved)
228 {
229 std::cout << "Found solution:" << std::endl;
231
232 ss.getSolutionPath().asGeometric().printAsMatrix(std::cout);
233 }
234 else
235 std::cout << "No solution found" << std::endl;
236}
237
238int main(int /*argc*/, char ** /*argv*/)
239{
240 std::cout << "OMPL version: " << OMPL_VERSION << std::endl;
241
242 planWithSimpleSetup();
243
244 return 0;
245}
const T * as(unsigned int index) const
Cast a component of this instance to a desired type.
Definition State.h:95
The lower and upper bounds for an Rn space.
A state in SE(2): (x, y, yaw).
void setY(double y)
Set the Y component of the state.
double getYaw() const
Get the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
double getY() const
Get the Y component of the state.
void setX(double x)
Set the X component of the state.
void setYaw(double yaw)
Set the yaw component of the state. This is the rotation in plane, with respect to the Z axis.
double getX() const
Get the X component of the state.
The definition of a state in SO(2).
A state space representing SO(2). The distance function and interpolation take into account angle wra...
void enforceBounds(State *state) const override
Normalize the value of the state to the interval [-Pi, Pi).
Definition of a scoped state.
Definition ScopedState.h:57
void setStateValidityChecker(const StateValidityCheckerPtr &svc)
Set the instance of the state validity checker to use. Parallel implementations of planners assume th...
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
ompl::control::Control ControlType
Define the type of control allocated by this control space.
Definition of an abstract control.
Definition Control.h:48
const T * as() const
Cast this instance to a desired type.
Definition Control.h:64
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
A control space representing Rn.
Create the set of classes typically needed to solve a control problem.
Definition SimpleSetup.h:63
Space information containing necessary information for planning with controls. setup() needs to be ca...
Model the effect of controls on system states.
StatePropagator(SpaceInformation *si)
Constructor.
This namespace contains sampling based planning routines shared by both planning under geometric cons...
This namespace contains sampling based planning routines used by planning under differential constrai...
Definition Control.h:45
A class to store the exit status of Planner::solve().