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>
55namespace po = boost::program_options;
57std::string toString(
ob::State const *state,
unsigned int numDims)
61 for (
unsigned int i = 0; i < numDims; ++i)
63 s << st.yaw() <<
'\n';
68 return toString(state.
get(), state.
getSpace()->getDimension() - 1);
79 Environment(Environment
const &) =
default;
80 Environment(
double radius) : radius_{radius}
84 double distance(
const ob::State *state)
const
88 for (
unsigned int i = 0; i < 3; ++i)
90 d = std::fmod(std::abs((*s)[i]), 2. * radius_) - radius_;
93 return std::sqrt(dist);
95 bool isValid(
const ob::State *state)
const
97 return distance(state) > .75 * radius_;
107 OptObjective(
const ob::SpaceInformationPtr &si,
const Environment &env,
bool enableMotionCostInterpolation =
false)
111 ob::Cost stateCost(ob::State
const *state)
const override
113 return ob::Cost(1. / (env_.distance(state) + .1));
123 unsigned int numDims = path.getSpaceInformation()->getStateDimension() - 1;
124 for (
auto const &state : path.getStates())
125 if (!env.isValid(state))
128 std::cout << env.distance(state) <<
' ' << toString(state, numDims);
131 std::cout <<
"Path is not valid!" << std::endl;
135ob::PlannerPtr allocPlanner(ob::SpaceInformationPtr
const &si, std::string
const &plannerName)
137 if (plannerName ==
"rrtstar")
139 auto planner(std::make_shared<og::RRTstar>(si));
140 planner->setRange(1);
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")
149 auto planner(std::make_shared<og::SST>(si));
150 planner->setSelectionRadius(0.05);
151 planner->setPruningRadius(0.01);
154 if (plannerName ==
"aps")
158 planner->setHybridize(
false);
162 if (plannerName !=
"rrt")
163 OMPL_ERROR(
"Unknown planner specified; defaulting to RRT");
165 return std::make_shared<og::RRT>(si);
168template <
class Space>
171 auto path = start.
getSpace()->as<Space>()->getPath(start.
get(), goal.
get());
174#if ENABLE_PROFILING == 0
175 std::cout <<
"start: " << toString(start);
176 std::cout <<
"goal: " << toString(goal);
178 throw std::runtime_error(
"Could not find a valid path");
183template <
class Space>
187 unsigned int success;
189 const auto &name = start.
getSpace()->getName();
193 auto path = getPath<Space>(start, goal);
195 length = path.length();
196 if constexpr (!std::is_same_v<Space, ob::VanaStateSpace>)
197 type = (
char)path.category();
199 catch (std::runtime_error &e)
202 length = std::numeric_limits<double>::quiet_NaN();
204 logfile <<
',' << success <<
',' << length <<
',' << type;
207template <
class Space>
210 auto path = getPath<Space>(start, goal);
211 auto space = start.
getSpace()->as<Space>();
226 if (!pathName.empty())
228 std::ofstream outfile(pathName);
229 for (
double t = 0.; t <= 1.001; t += .001)
231 space->interpolate(start.
get(), goal.
get(), t, path, state.get());
232 outfile << t <<
' ' << toString(state);
235 std::cout <<
"start: " << toString(start) <<
"goal: " << toString(goal) <<
"path: " << path <<
'\n';
239 std::string
const &plannerName, std::string
const &pathName)
241 auto const &space = start.
getSpace();
243 Environment env(radius);
245 setup.setStartAndGoalStates(start, goal);
246 setup.setStateValidityChecker([env](
const ob::State *state) {
return env.isValid(state); });
249 setup.getSpaceInformation()->setStateValidityCheckingResolution(0.001);
250 setup.setPlanner(allocPlanner(setup.getSpaceInformation(), plannerName));
253 auto result = setup.solve(timeLimit);
257 if (!pathName.empty())
259 auto path = setup.getSolutionPath();
260 if (!path.checkAndRepair(100).second)
261 std::cout <<
"Path is in collision!" << std::endl;
265 std::ofstream outfile(pathName);
266 path.printAsMatrix(outfile);
271 std::cout <<
"Approximate solution. Distance to goal is "
272 << setup.getProblemDefinition()->getSolutionDifference() << std::endl;
274 std::cout <<
"Path length is " << setup.getSolutionPath().length() << std::endl;
277void benchmark(
unsigned numSamples,
double radius,
double maxPitch)
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);
290 std::vector<double> start(5u, 0.);
301 vanaowenStart = start;
304 std::ofstream logfile(
"benchmark.csv");
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";
308 for (
unsigned int i = 0; i < numSamples; ++i)
310 vanaowenGoal.random();
311 vanaGoal = vanaowenGoal.reals();
312 owenGoal = vanaowenGoal.reals();
316 logfile << vanaowenGoal[0] <<
',' << vanaowenGoal[1] <<
',' << vanaowenGoal[2] <<
',' << vanaowenGoal[3] <<
','
319 saveStatistic<ob::OwenStateSpace>(logfile, owenStart, owenGoal);
320 saveStatistic<ob::VanaStateSpace>(logfile, vanaStart, vanaGoal);
321 saveStatistic<ob::VanaOwenStateSpace>(logfile, vanaowenStart, vanaowenGoal);
326int main(
int argc,
char *argv[])
330 std::string pathName;
331 double radius, maxPitch, timeLimit;
333 std::string plannerName{
"rrt"};
334 po::options_description desc(
"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");
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),
361 if ((vm.count(
"help") != 0u) || argc == 1)
363 std::cout << desc <<
"\n";
367 ob::StateSpacePtr space = [&]() -> ob::StateSpacePtr
373 if (vm.count(
"vana") != 0)
375 auto space = std::make_shared<ob::VanaStateSpace>(radius, maxPitch);
377 space->setBounds(bounds);
380 else if (vm.count(
"vanaowen") != 0)
382 auto space = std::make_shared<ob::VanaOwenStateSpace>(radius, maxPitch);
384 space->setBounds(bounds);
389 auto space = std::make_shared<ob::OwenStateSpace>(radius, maxPitch);
390 space->setBounds(bounds);
397 if (vm.count(
"start") == 0u)
399 for (
unsigned int i = 0; i < space->getDimension(); ++i)
404 auto startVec = vm[
"start"].as<std::vector<double>>();
405 for (
unsigned int i = 0; i < space->getDimension(); ++i)
406 start[i] = startVec[i];
409 if (vm.count(
"goal") == 0u)
412 Environment env(radius);
416 }
while (--i > 0 && !env.isValid(goal.
get()));
418 throw std::runtime_error(
"Could not sample a valid goal state");
422 auto goalVec = vm[
"goal"].as<std::vector<double>>();
423 for (
unsigned int i = 0; i < space->getDimension(); ++i)
424 goal[i] = goalVec[i];
428 benchmark(numSamples, radius, maxPitch);
429 else if (vm.count(
"plan") != 0u)
430 computePlan(start, goal, radius, timeLimit, plannerName, pathName);
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);
438 savePath<ob::OwenStateSpace>(start, goal, pathName);
441 catch (std::exception &e)
443 std::cerr <<
"error: " << e.what() <<
"\n";
448 std::cerr <<
"Exception of unknown type!\n";
const T * as(unsigned int index) const
Cast a component of this instance to a desired type.
The lower and upper bounds for an Rn space.
Definition of a scoped state.
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 of an abstract state.
const T * as() const
Cast this instance to a desired type.
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...
Kinematic Planning by Interior-Exterior Cell Exploration.
Definition of a geometric path.
Create the set of classes typically needed to solve a geometric problem.
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
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.