38 #include "../KinematicChain.h"
39 #include "QuotientSpacePlanningCommon.h"
40 #include <ompl/geometric/planners/quotientspace/QRRT.h>
41 #include <ompl/base/SpaceInformation.h>
42 #include <ompl/tools/benchmark/Benchmark.h>
44 const unsigned int numLinks = 15;
45 const double linkLength = 1.0 / numLinks;
46 const double narrowPassageWidth =
log((
double)numLinks) / (double)numLinks;
49 std::vector<Environment> envs;
51 ob::PlannerPtr GetQRRT(std::vector<int> sequenceLinks, ob::SpaceInformationPtr si, ob::ProblemDefinitionPtr pdef)
54 std::vector<ob::SpaceInformationPtr> si_vec;
56 for (
unsigned int k = 0; k < sequenceLinks.size(); k++)
58 int links = sequenceLinks.at(k);
59 assert(links < numLinks);
61 OMPL_INFORM(
"Create QuotientSpace Chain with %d links.", links);
62 auto spaceK(std::make_shared<KinematicChainSpace>(links, linkLength, &envs.at(links)));
64 auto siK = std::make_shared<ob::SpaceInformation>(spaceK);
65 siK->setStateValidityChecker(std::make_shared<KinematicChainValidityChecker>(siK));
67 si_vec.push_back(siK);
70 OMPL_INFORM(
"Add Original Chain with %d links.", numLinks);
73 auto planner = std::make_shared<og::QRRT>(si_vec);
74 planner->setProblemDefinition(pdef);
76 std::string qName =
"QuotientSpaceRRT[";
77 for (
unsigned int k = 0; k < sequenceLinks.size(); k++)
79 int links = sequenceLinks.at(k);
80 qName += std::to_string(links) +
",";
82 qName += std::to_string(numLinks);
84 planner->setName(qName);
90 Environment env = createHornEnvironment(numLinks, narrowPassageWidth);
91 OMPL_INFORM(
"Original Chain has %d links", numLinks);
92 OMPL_INFORM(
"Creating Horn Environment with width %f.", narrowPassageWidth);
93 envs.push_back(createHornEnvironment(1, narrowPassageWidth));
94 for (
unsigned int k = 1; k < numLinks; k++)
96 envs.push_back(createHornEnvironment(k, narrowPassageWidth));
99 auto chain(std::make_shared<KinematicChainSpace>(numLinks, linkLength, &env));
102 ss.setStateValidityChecker(std::make_shared<KinematicChainValidityChecker>(ss.getSpaceInformation()));
105 std::vector<double> startVec(numLinks, boost::math::constants::pi<double>() / (
double)numLinks);
106 std::vector<double> goalVec(numLinks, 0);
108 goalVec[0] = boost::math::constants::pi<double>() - .001;
110 chain->copyFromReals(start.get(), startVec);
111 chain->copyFromReals(goal.get(), goalVec);
112 ss.setStartAndGoalStates(start, goal);
114 double runtime_limit = 10, memory_limit = 1024;
118 b.addExperimentParameter(
"num_links",
"INTEGER", std::to_string(numLinks));
123 b.addPlanner(std::make_shared<ompl::geometric::STRIDE>(ss.getSpaceInformation()));
124 b.addPlanner(std::make_shared<ompl::geometric::EST>(ss.getSpaceInformation()));
125 b.addPlanner(std::make_shared<ompl::geometric::KPIECE1>(ss.getSpaceInformation()));
126 b.addPlanner(std::make_shared<ompl::geometric::RRT>(ss.getSpaceInformation()));
127 b.addPlanner(std::make_shared<ompl::geometric::PRM>(ss.getSpaceInformation()));
129 b.addPlanner(GetQRRT(std::vector<int>{3}, ss.getSpaceInformation(), ss.getProblemDefinition()));
130 b.addPlanner(GetQRRT(std::vector<int>{2}, ss.getSpaceInformation(), ss.getProblemDefinition()));
131 b.addPlanner(GetQRRT(std::vector<int>{3, 5, 9}, ss.getSpaceInformation(), ss.getProblemDefinition()));
132 b.addPlanner(GetQRRT(std::vector<int>{3, 11}, ss.getSpaceInformation(), ss.getProblemDefinition()));
133 b.addPlanner(GetQRRT(std::vector<int>{10}, ss.getSpaceInformation(), ss.getProblemDefinition()));
134 b.addPlanner(GetQRRT(std::vector<int>{12}, ss.getSpaceInformation(), ss.getProblemDefinition()));
135 b.addPlanner(GetQRRT(std::vector<int>{8, 13}, ss.getSpaceInformation(), ss.getProblemDefinition()));
136 b.addPlanner(GetQRRT(std::vector<int>{}, ss.getSpaceInformation(), ss.getProblemDefinition()));
137 b.addPlanner(GetQRRT(std::vector<int>{2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14}, ss.getSpaceInformation(),
138 ss.getProblemDefinition()));
140 b.benchmark(request);
141 b.saveResultsToFile(boost::str(boost::format(
"kinematic_%i.log") % numLinks).c_str());
143 printBenchmarkResults(b);
Definition of a scoped state.
Create the set of classes typically needed to solve a geometric problem.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
void log(const char *file, int line, LogLevel level, const char *m,...)
Root level logging function. This should not be invoked directly, but rather used via a logging macro...