Loading...
Searching...
No Matches
DubinsAirplane.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2024, Metron, Inc.
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 Metron, Inc. 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: Mark Moll */
36
37#include <ompl/base/spaces/OwenStateSpace.h>
38#include <ompl/base/spaces/VanaStateSpace.h>
39#include <ompl/base/spaces/VanaOwenStateSpace.h>
40#include <ompl/base/objectives/StateCostIntegralObjective.h>
41#include <ompl/geometric/SimpleSetup.h>
42#include <ompl/geometric/planners/rrt/RRT.h>
43#include <ompl/geometric/planners/rrt/RRTstar.h>
44#include <ompl/geometric/planners/kpiece/KPIECE1.h>
45#include <ompl/geometric/planners/est/EST.h>
46#include <ompl/geometric/planners/sst/SST.h>
47#include <ompl/geometric/planners/AnytimePathShortening.h>
48#include <ompl/tools/debug/Profiler.h>
49#include <boost/program_options.hpp>
50#include <cmath>
51#include <fstream>
52
53namespace ob = ompl::base;
54namespace og = ompl::geometric;
55namespace po = boost::program_options;
56
57std::string toString(ob::State const *state, unsigned int numDims)
58{
59 const auto &st = *state->as<ob::VanaStateSpace::StateType>();
60 std::stringstream s;
61 for (unsigned int i = 0; i < numDims; ++i)
62 s << st[i] << ' ';
63 s << st.yaw() << '\n';
64 return s.str();
65}
66std::string toString(ob::ScopedState<> const &state)
67{
68 return toString(state.get(), state.getSpace()->getDimension() - 1);
69}
70
71// This class models a world tiled by 3D spheres. The speres are 2*radius apart along
72// the X-, Y-, and Z-axis.
73// The radius of each sphere is .75*radius.
74// The spheres are positioned at ((2*i+1)*radius, (2*j+1)*radius, (2*k+1)*radius),
75// for i,j,k = ... , -2, -1, 0, 1, 2, ...
76class Environment
77{
78public:
79 Environment(Environment const &) = default;
80 Environment(double radius) : radius_{radius}
81 {
82 }
83
84 double distance(const ob::State *state) const
85 {
86 auto s = state->as<ob::VanaStateSpace::StateType>();
87 double dist = 0., d;
88 for (unsigned int i = 0; i < 3; ++i)
89 {
90 d = std::fmod(std::abs((*s)[i]), 2. * radius_) - radius_;
91 dist += d * d;
92 }
93 return std::sqrt(dist);
94 }
95 bool isValid(const ob::State *state) const
96 {
97 return distance(state) > .75 * radius_;
98 }
99
100protected:
101 double radius_;
102};
103
104class OptObjective : public ob::StateCostIntegralObjective
105{
106public:
107 OptObjective(const ob::SpaceInformationPtr &si, const Environment &env, bool enableMotionCostInterpolation = false)
108 : ob::StateCostIntegralObjective(si, enableMotionCostInterpolation), env_(env)
109 {
110 }
111 ob::Cost stateCost(ob::State const *state) const override
112 {
113 return ob::Cost(1. / (env_.distance(state) + .1));
114 }
115
116protected:
117 Environment env_;
118};
119
120bool checkPath(og::PathGeometric &path, Environment const &env)
121{
122 bool result = true;
123 unsigned int numDims = path.getSpaceInformation()->getStateDimension() - 1;
124 for (auto const &state : path.getStates())
125 if (!env.isValid(state))
126 {
127 result = false;
128 std::cout << env.distance(state) << ' ' << toString(state, numDims);
129 }
130 if (!result)
131 std::cout << "Path is not valid!" << std::endl;
132 return result;
133}
134
135ob::PlannerPtr allocPlanner(ob::SpaceInformationPtr const &si, std::string const &plannerName)
136{
137 if (plannerName == "rrtstar")
138 {
139 auto planner(std::make_shared<og::RRTstar>(si));
140 planner->setRange(1);
141 return planner;
142 }
143 if (plannerName == "est")
144 return std::make_shared<og::EST>(si);
145 if (plannerName == "kpiece")
146 return std::make_shared<og::KPIECE1>(si);
147 if (plannerName == "sst")
148 {
149 auto planner(std::make_shared<og::SST>(si));
150 planner->setSelectionRadius(0.05);
151 planner->setPruningRadius(0.01);
152 return planner;
153 }
154 if (plannerName == "aps")
155 {
158 planner->setHybridize(false);
159 return planner;
160 }
161
162 if (plannerName != "rrt")
163 OMPL_ERROR("Unknown planner specified; defaulting to RRT");
164
165 return std::make_shared<og::RRT>(si);
166}
167
168template <class Space>
169typename Space::PathType getPath(ob::ScopedState<> const &start, ob::ScopedState<> const &goal)
170{
171 auto path = start.getSpace()->as<Space>()->getPath(start.get(), goal.get());
172 if (!path)
173 {
174#if ENABLE_PROFILING == 0
175 std::cout << "start: " << toString(start);
176 std::cout << "goal: " << toString(goal);
177#endif
178 throw std::runtime_error("Could not find a valid path");
179 }
180 return *path;
181}
182
183template <class Space>
184void saveStatistic(std::ostream &logfile, ob::ScopedState<> const &start, ob::ScopedState<> const &goal)
185{
186 double length;
187 unsigned int success;
188 char type = '?';
189 const auto &name = start.getSpace()->getName();
190 try
191 {
193 auto path = getPath<Space>(start, goal);
194 success = 1;
195 length = path.length();
196 if constexpr (!std::is_same_v<Space, ob::VanaStateSpace>)
197 type = (char)path.category();
198 }
199 catch (std::runtime_error &e)
200 {
201 success = 0;
202 length = std::numeric_limits<double>::quiet_NaN();
203 }
204 logfile << ',' << success << ',' << length << ',' << type;
205}
206
207template <class Space>
208void savePath(ob::ScopedState<> const &start, ob::ScopedState<> const &goal, std::string const &pathName)
209{
210 auto path = getPath<Space>(start, goal);
211 auto space = start.getSpace()->as<Space>();
212 ob::ScopedState<Space> state(start);
213 // double dist = path.length(), d1, d2;
214 // for (unsigned i=1; i<100; ++i)
215 // {
216 // space->interpolate(start.get(), goal.get(), (double)i/50., path, st);
217 // d1 = space->distance(start.get(), state.get());
218 // d2 = space->distance(state.get(), goal.get());
219 // if (std::abs(d1 + d2 - dist) > .01)
220 // {
221 // std::cout << i << "," << dist << "," << d1 << "," << d2 << "," << d1+d2-dist << "," << toString(state) <<
222 // '\n';
223 // }
224 // }
225
226 if (!pathName.empty())
227 {
228 std::ofstream outfile(pathName);
229 for (double t = 0.; t <= 1.001; t += .001)
230 {
231 space->interpolate(start.get(), goal.get(), t, path, state.get());
232 outfile << t << ' ' << toString(state);
233 }
234 }
235 std::cout << "start: " << toString(start) << "goal: " << toString(goal) << "path: " << path << '\n';
236}
237
238void computePlan(ob::ScopedState<> const &start, ob::ScopedState<> &goal, double radius, double timeLimit,
239 std::string const &plannerName, std::string const &pathName)
240{
241 auto const &space = start.getSpace();
242 og::SimpleSetup setup(space);
243 Environment env(radius);
244
245 setup.setStartAndGoalStates(start, goal);
246 setup.setStateValidityChecker([env](const ob::State *state) { return env.isValid(state); });
247 // setup.setStateValidityChecker([](const ob::State*){ return true; });
248 // setup.setOptimizationObjective(std::make_shared<OptObjective>(setup.getSpaceInformation(), env));
249 setup.getSpaceInformation()->setStateValidityCheckingResolution(0.001);
250 setup.setPlanner(allocPlanner(setup.getSpaceInformation(), plannerName));
251 setup.setup();
252 setup.print();
253 auto result = setup.solve(timeLimit);
254 if (result)
255 {
256 // setup.simplifySolution();
257 if (!pathName.empty())
258 {
259 auto path = setup.getSolutionPath();
260 if (!path.checkAndRepair(100).second)
261 std::cout << "Path is in collision!" << std::endl;
262 path.interpolate();
263 if (true) // checkPath(path, radius))
264 {
265 std::ofstream outfile(pathName);
266 path.printAsMatrix(outfile);
267 }
268 }
269 }
271 std::cout << "Approximate solution. Distance to goal is "
272 << setup.getProblemDefinition()->getSolutionDifference() << std::endl;
273 if (result)
274 std::cout << "Path length is " << setup.getSolutionPath().length() << std::endl;
275}
276
277void benchmark(unsigned numSamples, double radius, double maxPitch)
278{
279 ob::RealVectorBounds bounds(3);
280 bounds.setLow(-10);
281 bounds.setHigh(10);
282
283 auto owenSpace = std::make_shared<ob::OwenStateSpace>(radius, maxPitch);
284 auto vanaSpace = std::make_shared<ob::VanaStateSpace>(radius, maxPitch);
285 auto vanaowenSpace = std::make_shared<ob::VanaOwenStateSpace>(radius, maxPitch);
286 owenSpace->setBounds(bounds);
287 vanaSpace->setBounds(bounds);
288 vanaowenSpace->setBounds(bounds);
289
290 std::vector<double> start(5u, 0.);
291
292 ob::ScopedState<> owenStart(owenSpace);
293 ob::ScopedState<> owenGoal(owenSpace);
294 ob::ScopedState<> vanaStart(vanaSpace);
295 ob::ScopedState<> vanaGoal(vanaSpace);
296 ob::ScopedState<> vanaowenStart(vanaowenSpace);
297 ob::ScopedState<> vanaowenGoal(vanaowenSpace);
298
299 owenStart = start;
300 vanaStart = start;
301 vanaowenStart = start;
302
304 std::ofstream logfile("benchmark.csv");
305 logfile
306 << "X,Y,Z,pitch,yaw,owen_success,owen_length,owen_category,vana_success,vana_length,vana_category,vanaowen_success,vanaowen_length,vanaowen_category\n";
307
308 for (unsigned int i = 0; i < numSamples; ++i)
309 {
310 vanaowenGoal.random();
311 vanaGoal = vanaowenGoal.reals();
312 owenGoal = vanaowenGoal.reals();
313 owenGoal->as<ob::OwenStateSpace::StateType>()->yaw() =
314 vanaowenGoal->as<ob::VanaOwenStateSpace::StateType>()->yaw();
315
316 logfile << vanaowenGoal[0] << ',' << vanaowenGoal[1] << ',' << vanaowenGoal[2] << ',' << vanaowenGoal[3] << ','
317 << vanaowenGoal[4];
318
319 saveStatistic<ob::OwenStateSpace>(logfile, owenStart, owenGoal);
320 saveStatistic<ob::VanaStateSpace>(logfile, vanaStart, vanaGoal);
321 saveStatistic<ob::VanaOwenStateSpace>(logfile, vanaowenStart, vanaowenGoal);
322 logfile << '\n';
323 }
324}
325
326int main(int argc, char *argv[])
327{
328 try
329 {
330 std::string pathName;
331 double radius, maxPitch, timeLimit;
332 unsigned numSamples;
333 std::string plannerName{"rrt"};
334 po::options_description desc("Options");
335 // clang-format off
336 desc.add_options()
337 ("help", "show help message")
338 ("owen", "generate a owen path starting from (x,y,z,yaw)=(0,0,0,0) to a random pose")
339 ("vana", "generate a Vana path starting from (x,y,z,pitch,yaw)=(0,0,0,0,0) to a random pose")
340 ("vanaowen", "generate a Vana-Owen path starting from (x,y,z,pitch,yaw)=(0,0,0,0,0) to a random pose")
341 ("plan", "use a planner to plan a path to a random pose in space with obstacles")
342 ("savepath", po::value<std::string>(&pathName), "save an (approximate) solution path to file")
343 ("start", po::value<std::vector<double>>()->multitoken(),
344 "use (x,y,z,[pitch,]yaw) as the start")
345 ("goal", po::value<std::vector<double>>()->multitoken(),
346 "use (x,y,z,[pitch,]yaw) as the goal instead of a random state")
347 ("radius", po::value<double>(&radius)->default_value(1.), "turn radius")
348 ("maxpitch", po::value<double>(&maxPitch)->default_value(.5), "maximum pitch angle")
349 ("planner", po::value<std::string>(&plannerName)->default_value("kpiece"),
350 "planning algorithm to use (rrt, rrtstar, est, kpiece, sst, aps)")
351 ("time", po::value<double>(&timeLimit)->default_value(10), "time limit for planning")
352 ("benchmark", po::value<unsigned int>(&numSamples)->default_value(0), "benchmark performance with given number of random goal positions");
353 // clang-format on
354
355 po::variables_map vm;
356 po::store(po::parse_command_line(argc, argv, desc,
357 po::command_line_style::unix_style ^ po::command_line_style::allow_short),
358 vm);
359 po::notify(vm);
360
361 if ((vm.count("help") != 0u) || argc == 1)
362 {
363 std::cout << desc << "\n";
364 return 1;
365 }
366
367 ob::StateSpacePtr space = [&]() -> ob::StateSpacePtr
368 {
369 // set the bounds for the R^3 part of the space
370 ob::RealVectorBounds bounds(3);
371 bounds.setLow(-10);
372 bounds.setHigh(10);
373 if (vm.count("vana") != 0)
374 {
375 auto space = std::make_shared<ob::VanaStateSpace>(radius, maxPitch);
376 // space->setTolerance(1e-16);
377 space->setBounds(bounds);
378 return space;
379 }
380 else if (vm.count("vanaowen") != 0)
381 {
382 auto space = std::make_shared<ob::VanaOwenStateSpace>(radius, maxPitch);
383 // space->setTolerance(1e-16);
384 space->setBounds(bounds);
385 return space;
386 }
387 else
388 {
389 auto space = std::make_shared<ob::OwenStateSpace>(radius, maxPitch);
390 space->setBounds(bounds);
391 return space;
392 }
393 }();
394 ob::ScopedState<> start(space);
395 ob::ScopedState<> goal(space);
396
397 if (vm.count("start") == 0u)
398 {
399 for (unsigned int i = 0; i < space->getDimension(); ++i)
400 start[i] = 0.;
401 }
402 else
403 {
404 auto startVec = vm["start"].as<std::vector<double>>();
405 for (unsigned int i = 0; i < space->getDimension(); ++i)
406 start[i] = startVec[i];
407 }
408
409 if (vm.count("goal") == 0u)
410 {
411 unsigned i = 100;
412 Environment env(radius);
413 do
414 {
415 goal.random();
416 } while (--i > 0 && !env.isValid(goal.get()));
417 if (i == 0)
418 throw std::runtime_error("Could not sample a valid goal state");
419 }
420 else
421 {
422 auto goalVec = vm["goal"].as<std::vector<double>>();
423 for (unsigned int i = 0; i < space->getDimension(); ++i)
424 goal[i] = goalVec[i];
425 }
426
427 if (numSamples > 0)
428 benchmark(numSamples, radius, maxPitch);
429 else if (vm.count("plan") != 0u)
430 computePlan(start, goal, radius, timeLimit, plannerName, pathName);
431 else
432 {
433 if (vm.count("vana") != 0u)
434 savePath<ob::VanaStateSpace>(start, goal, pathName);
435 else if (vm.count("vanaowen") != 0u)
436 savePath<ob::VanaOwenStateSpace>(start, goal, pathName);
437 else
438 savePath<ob::OwenStateSpace>(start, goal, pathName);
439 }
440 }
441 catch (std::exception &e)
442 {
443 std::cerr << "error: " << e.what() << "\n";
444 return 1;
445 }
446 catch (...)
447 {
448 std::cerr << "Exception of unknown type!\n";
449 }
450
451 return 0;
452}
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.
Definition of a scoped state.
Definition ScopedState.h:57
const StateSpacePtr & getSpace() const
Get the state space that the state corresponds to.
void random()
Set this state to a random value (uniform).
StateType * get()
Returns a pointer to the contained state.
Defines optimization objectives where path cost can be represented as a path integral over a cost fun...
StateCostIntegralObjective(const SpaceInformationPtr &si, bool enableMotionCostInterpolation=false)
If enableMotionCostInterpolation is set to true, then calls to motionCost() will divide the motion se...
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
static std::shared_ptr< AnytimePathShortening > createPlanner(const base::SpaceInformationPtr &si, unsigned int numPlanners=std::max(1u, std::thread::hardware_concurrency()))
Factory for creating a shared pointer to an AnytimePathShortening instance with numPlanners instances...
Expansive Space Trees.
Definition EST.h:66
Kinematic Planning by Interior-Exterior Cell Exploration.
Definition KPIECE1.h:72
Definition of a geometric path.
Create the set of classes typically needed to solve a geometric problem.
Definition SimpleSetup.h:63
This instance will call Profiler::begin() when constructed and Profiler::end() when it goes out of sc...
Definition Profiler.h:82
static void Start()
Start counting time.
Definition Profiler.h:144
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
This namespace contains sampling based planning routines shared by both planning under geometric cons...
This namespace contains code that is specific to planning under geometric constraints.
@ APPROXIMATE_SOLUTION
The planner found an approximate solution.