Loading...
Searching...
No Matches
RigidBodyPlanningWithIntegrationAndControls.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, 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: Ioan Sucan */
36
37#include <ompl/control/SpaceInformation.h>
38#include <ompl/base/goals/GoalState.h>
39#include <ompl/base/spaces/SE2StateSpace.h>
40#include <ompl/control/spaces/RealVectorControlSpace.h>
41#include <ompl/control/planners/kpiece/KPIECE1.h>
42#include <ompl/control/planners/rrt/RRT.h>
43#include <ompl/control/SimpleSetup.h>
44#include <ompl/config.h>
45#include <iostream>
46#include <valarray>
47#include <limits>
48
49namespace ob = ompl::base;
50namespace oc = ompl::control;
51
53class KinematicCarModel
54{
55public:
56 KinematicCarModel(const ob::StateSpace *space) : space_(space), carLength_(0.2)
57 {
58 }
59
61 void operator()(const ob::State *state, const oc::Control *control, std::valarray<double> &dstate) const
62 {
63 const double *u = control->as<oc::RealVectorControlSpace::ControlType>()->values;
64 const double theta = state->as<ob::SE2StateSpace::StateType>()->getYaw();
65
66 dstate.resize(3);
67 dstate[0] = u[0] * cos(theta);
68 dstate[1] = u[0] * sin(theta);
69 dstate[2] = u[0] * tan(u[1]) / carLength_;
70 }
71
73 void update(ob::State *state, const std::valarray<double> &dstate) const
74 {
76 s.setX(s.getX() + dstate[0]);
77 s.setY(s.getY() + dstate[1]);
78 s.setYaw(s.getYaw() + dstate[2]);
79 space_->enforceBounds(state);
80 }
81
82private:
83 const ob::StateSpace *space_;
84 const double carLength_;
85};
86
88template <typename F>
89class EulerIntegrator
90{
91public:
92 EulerIntegrator(const ob::StateSpace *space, double timeStep) : space_(space), timeStep_(timeStep), ode_(space)
93 {
94 }
95
96 void propagate(const ob::State *start, const oc::Control *control, const double duration, ob::State *result) const
97 {
98 double t = 0;
99 std::valarray<double> dstate;
100 space_->copyState(result, start);
101 while (t + timeStep_ < duration + std::numeric_limits<double>::epsilon())
102 {
103 ode_(result, control, dstate);
104 ode_.update(result, timeStep_ * dstate);
105 t += timeStep_;
106 }
107 if (t + std::numeric_limits<double>::epsilon() < duration)
108 {
109 ode_(result, control, dstate);
110 ode_.update(result, (duration - t) * dstate);
111 }
112 }
113
114 double getTimeStep() const
115 {
116 return timeStep_;
117 }
118
119 void setTimeStep(double timeStep)
120 {
121 timeStep_ = timeStep;
122 }
123
124private:
125 const ob::StateSpace *space_;
126 double timeStep_;
127 F ode_;
128};
129
130bool isStateValid(const oc::SpaceInformation *si, const ob::State *state)
131{
132 // ob::ScopedState<ob::SE2StateSpace>
134 const auto *se2state = state->as<ob::SE2StateSpace::StateType>();
135
137 const auto *pos = se2state->as<ob::RealVectorStateSpace::StateType>(0);
138
140 const auto *rot = se2state->as<ob::SO2StateSpace::StateType>(1);
141
143
144 // return a value that is always true but uses the two variables we define, so we avoid compiler warnings
145 return si->satisfiesBounds(state) && (const void *)rot != (const void *)pos;
146}
147
149class DemoControlSpace : public oc::RealVectorControlSpace
150{
151public:
152 DemoControlSpace(const ob::StateSpacePtr &stateSpace) : oc::RealVectorControlSpace(stateSpace, 2)
153 {
154 }
155};
156
157class DemoStatePropagator : public oc::StatePropagator
158{
159public:
160 DemoStatePropagator(oc::SpaceInformation *si) : oc::StatePropagator(si), integrator_(si->getStateSpace().get(), 0.0)
161 {
162 }
163
164 void propagate(const ob::State *state, const oc::Control *control, const double duration,
165 ob::State *result) const override
166 {
167 integrator_.propagate(state, control, duration, result);
168 }
169
170 void setIntegrationTimeStep(double timeStep)
171 {
172 integrator_.setTimeStep(timeStep);
173 }
174
175 double getIntegrationTimeStep() const
176 {
177 return integrator_.getTimeStep();
178 }
179
180 EulerIntegrator<KinematicCarModel> integrator_;
181};
182
184
185void planWithSimpleSetup()
186{
188 auto space(std::make_shared<ob::SE2StateSpace>());
189
191 ob::RealVectorBounds bounds(2);
192 bounds.setLow(-1);
193 bounds.setHigh(1);
194
195 space->setBounds(bounds);
196
197 // create a control space
198 auto cspace(std::make_shared<DemoControlSpace>(space));
199
200 // set the bounds for the control space
201 ob::RealVectorBounds cbounds(2);
202 cbounds.setLow(-0.3);
203 cbounds.setHigh(0.3);
204
205 cspace->setBounds(cbounds);
206
207 // define a simple setup class
208 oc::SimpleSetup ss(cspace);
209
211 oc::SpaceInformation *si = ss.getSpaceInformation().get();
212 ss.setStateValidityChecker([si](const ob::State *state) { return isStateValid(si, state); });
213
215 auto propagator(std::make_shared<DemoStatePropagator>(si));
216 ss.setStatePropagator(propagator);
217
220 start->setX(-0.5);
221 start->setY(0.0);
222 start->setYaw(0.0);
223
226 goal->setX(0.0);
227 goal->setY(0.5);
228 goal->setYaw(0.0);
229
231 ss.setStartAndGoalStates(start, goal, 0.05);
232
234 ss.setup();
235 propagator->setIntegrationTimeStep(si->getPropagationStepSize());
236
238 ob::PlannerStatus solved = ss.solve(10.0);
239
240 if (solved)
241 {
242 std::cout << "Found solution:" << std::endl;
244
245 ss.getSolutionPath().asGeometric().printAsMatrix(std::cout);
246 }
247 else
248 std::cout << "No solution found" << std::endl;
249}
250
251int main(int /*argc*/, char ** /*argv*/)
252{
253 std::cout << "OMPL version: " << OMPL_VERSION << std::endl;
254
255 planWithSimpleSetup();
256
257 return 0;
258}
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).
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.
const T * as() const
Cast this instance to a desired type.
Definition Control.h:64
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.
virtual void propagate(const base::State *state, const Control *control, double duration, base::State *result) const =0
Propagate from a state, given a control, for some specified amount of time (the amount of time can al...
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().