Loading...
Searching...
No Matches
RigidBodyPlanningWithControls.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/planners/est/EST.h>
44#include <ompl/control/planners/syclop/SyclopRRT.h>
45#include <ompl/control/planners/syclop/SyclopEST.h>
46#include <ompl/control/planners/pdst/PDST.h>
47#include <ompl/control/planners/syclop/GridDecomposition.h>
48#include <ompl/control/SimpleSetup.h>
49#include <ompl/config.h>
50#include <iostream>
51
52namespace ob = ompl::base;
53namespace oc = ompl::control;
54
55// a decomposition is only needed for SyclopRRT and SyclopEST
56class MyDecomposition : public oc::GridDecomposition
57{
58public:
59 MyDecomposition(const int length, const ob::RealVectorBounds &bounds) : GridDecomposition(length, 2, bounds)
60 {
61 }
62 void project(const ob::State *s, std::vector<double> &coord) const override
63 {
64 coord.resize(2);
65 coord[0] = s->as<ob::SE2StateSpace::StateType>()->getX();
66 coord[1] = s->as<ob::SE2StateSpace::StateType>()->getY();
67 }
68
69 void sampleFullState(const ob::StateSamplerPtr &sampler, const std::vector<double> &coord,
70 ob::State *s) const override
71 {
72 sampler->sampleUniform(s);
73 s->as<ob::SE2StateSpace::StateType>()->setXY(coord[0], coord[1]);
74 }
75};
76
77bool isStateValid(const oc::SpaceInformation *si, const ob::State *state)
78{
79 // ob::ScopedState<ob::SE2StateSpace>
80 // cast the abstract state type to the type we expect
81 const auto *se2state = state->as<ob::SE2StateSpace::StateType>();
82
83 // extract the first component of the state and cast it to what we expect
84 const auto *pos = se2state->as<ob::RealVectorStateSpace::StateType>(0);
85
86 // extract the second component of the state and cast it to what we expect
87 const auto *rot = se2state->as<ob::SO2StateSpace::StateType>(1);
88
89 // check validity of state defined by pos & rot
90
91 // return a value that is always true but uses the two variables we define, so we avoid compiler warnings
92 return si->satisfiesBounds(state) && (const void *)rot != (const void *)pos;
93}
94
95void propagate(const ob::State *start, const oc::Control *control, const double duration, ob::State *result)
96{
97 const auto *se2state = start->as<ob::SE2StateSpace::StateType>();
98 const double *pos = se2state->as<ob::RealVectorStateSpace::StateType>(0)->values;
99 const double rot = se2state->as<ob::SO2StateSpace::StateType>(1)->value;
100 const double *ctrl = control->as<oc::RealVectorControlSpace::ControlType>()->values;
101
102 result->as<ob::SE2StateSpace::StateType>()->setXY(pos[0] + ctrl[0] * duration * cos(rot),
103 pos[1] + ctrl[0] * duration * sin(rot));
104 result->as<ob::SE2StateSpace::StateType>()->setYaw(rot + ctrl[1] * duration);
105}
106
107void plan()
108{
109 // construct the state space we are planning in
110 auto space(std::make_shared<ob::SE2StateSpace>());
111
112 // set the bounds for the R^2 part of SE(2)
113 ob::RealVectorBounds bounds(2);
114 bounds.setLow(-1);
115 bounds.setHigh(1);
116
117 space->setBounds(bounds);
118
119 // create a control space
120 auto cspace(std::make_shared<oc::RealVectorControlSpace>(space, 2));
121
122 // set the bounds for the control space
123 ob::RealVectorBounds cbounds(2);
124 cbounds.setLow(-0.3);
125 cbounds.setHigh(0.3);
126
127 cspace->setBounds(cbounds);
128
129 // construct an instance of space information from this control space
130 auto si(std::make_shared<oc::SpaceInformation>(space, cspace));
131
132 // set state validity checking for this space
133 si->setStateValidityChecker([&si](const ob::State *state) { return isStateValid(si.get(), state); });
134
135 // set the state propagation routine
136 si->setStatePropagator(propagate);
137
138 // create a start state
140 start->setX(-0.5);
141 start->setY(0.0);
142 start->setYaw(0.0);
143
144 // create a goal state
146 goal->setX(0.5);
147
148 // create a problem instance
149 auto pdef(std::make_shared<ob::ProblemDefinition>(si));
150
151 // set the start and goal states
152 pdef->setStartAndGoalStates(start, goal, 0.1);
153
154 // create a planner for the defined space
155 // auto planner(std::make_shared<oc::RRT>(si));
156 // auto planner(std::make_shared<oc::EST>(si));
157 // auto planner(std::make_shared<oc::KPIECE1>(si));
158 auto decomp(std::make_shared<MyDecomposition>(32, bounds));
159 auto planner(std::make_shared<oc::SyclopEST>(si, decomp));
160 // auto planner(std::make_shared<oc::SyclopRRT>(si, decomp));
161
162 // set the problem we are trying to solve for the planner
163 planner->setProblemDefinition(pdef);
164
165 // perform setup steps for the planner
166 planner->setup();
167
168 // print the settings for this space
169 si->printSettings(std::cout);
170
171 // print the problem settings
172 pdef->print(std::cout);
173
174 // attempt to solve the problem within ten seconds of planning time
175 ob::PlannerStatus solved = planner->ob::Planner::solve(10.0);
176
177 if (solved)
178 {
179 // get the goal representation from the problem definition (not the same as the goal state)
180 // and inquire about the found path
181 ob::PathPtr path = pdef->getSolutionPath();
182 std::cout << "Found solution:" << std::endl;
183
184 // print the path to screen
185 path->print(std::cout);
186 }
187 else
188 std::cout << "No solution found" << std::endl;
189}
190
191void planWithSimpleSetup()
192{
193 // construct the state space we are planning in
194 auto space(std::make_shared<ob::SE2StateSpace>());
195
196 // set the bounds for the R^2 part of SE(2)
197 ob::RealVectorBounds bounds(2);
198 bounds.setLow(-1);
199 bounds.setHigh(1);
200
201 space->setBounds(bounds);
202
203 // create a control space
204 auto cspace(std::make_shared<oc::RealVectorControlSpace>(space, 2));
205
206 // set the bounds for the control space
207 ob::RealVectorBounds cbounds(2);
208 cbounds.setLow(-0.3);
209 cbounds.setHigh(0.3);
210
211 cspace->setBounds(cbounds);
212
213 // define a simple setup class
214 oc::SimpleSetup ss(cspace);
215
216 // set the state propagation routine
217 ss.setStatePropagator(propagate);
218
219 // set state validity checking for this space
220 ss.setStateValidityChecker([&ss](const ob::State *state)
221 { return isStateValid(ss.getSpaceInformation().get(), state); });
222
223 // create a start state
225 start->setX(-0.5);
226 start->setY(0.0);
227 start->setYaw(0.0);
228
229 // create a goal state; use the hard way to set the elements
231 (*goal)[0]->as<ob::RealVectorStateSpace::StateType>()->values[0] = 0.0;
232 (*goal)[0]->as<ob::RealVectorStateSpace::StateType>()->values[1] = 0.5;
233 (*goal)[1]->as<ob::SO2StateSpace::StateType>()->value = 0.0;
234
235 // set the start and goal states
236 ss.setStartAndGoalStates(start, goal, 0.05);
237
238 // ss.setPlanner(std::make_shared<oc::PDST>(ss.getSpaceInformation()));
239 // ss.getSpaceInformation()->setMinMaxControlDuration(1,100);
240 // attempt to solve the problem within one second of planning time
241 ob::PlannerStatus solved = ss.solve(10.0);
242
243 if (solved)
244 {
245 std::cout << "Found solution:" << std::endl;
246 // print the path to screen
247
248 ss.getSolutionPath().printAsMatrix(std::cout);
249 }
250 else
251 std::cout << "No solution found" << std::endl;
252}
253
254int main(int /*argc*/, char ** /*argv*/)
255{
256 std::cout << "OMPL version: " << OMPL_VERSION << std::endl;
257
258 // plan();
259 //
260 // std::cout << std::endl << std::endl;
261 //
262 planWithSimpleSetup();
263
264 return 0;
265}
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).
The definition of a state in SO(2).
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
Definition of an abstract control.
Definition Control.h:48
A GridDecomposition is a Decomposition implemented using a grid.
GridDecomposition(int len, int dim, const base::RealVectorBounds &b)
Constructor. Creates a GridDecomposition as a hypercube with a given dimension, side length,...
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...
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().