QuotientSpacePlanningKinematicChain.cpp
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, University of Stuttgart
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 University of Stuttgart nor the names
18  * of its contributors may be used to endorse or promote products
19  * derived from this software without specific prior written
20  * permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Andreas Orthey */
37 
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>
43 
44 const unsigned int numLinks = 15;
45 const double linkLength = 1.0 / numLinks;
46 const double narrowPassageWidth = log((double)numLinks) / (double)numLinks;
47 
48 namespace ot = ompl::tools;
49 std::vector<Environment> envs;
50 
51 ob::PlannerPtr GetQRRT(std::vector<unsigned int> sequenceLinks, ob::SpaceInformationPtr si,
52  ob::ProblemDefinitionPtr pdef)
53 {
54  // ompl::msg::setLogLevel(ompl::msg::LOG_DEV2);
55  std::vector<ob::SpaceInformationPtr> si_vec;
56 
57  for (unsigned int k = 0; k < sequenceLinks.size(); k++)
58  {
59  auto links = sequenceLinks.at(k);
60  assert(links < numLinks);
61 
62  OMPL_INFORM("Create QuotientSpace Chain with %d links.", links);
63  auto spaceK(std::make_shared<KinematicChainSpace>(links, linkLength, &envs.at(links)));
64 
65  auto siK = std::make_shared<ob::SpaceInformation>(spaceK);
66  siK->setStateValidityChecker(std::make_shared<KinematicChainValidityChecker>(siK));
67  spaceK->setup();
68  si_vec.push_back(siK);
69  }
70 
71  OMPL_INFORM("Add Original Chain with %d links.", numLinks);
72  si_vec.push_back(si);
73 
74  auto planner = std::make_shared<og::QRRT>(si_vec);
75  planner->setProblemDefinition(pdef);
76 
77  std::string qName = "QuotientSpaceRRT[";
78  for (unsigned int k = 0; k < sequenceLinks.size(); k++)
79  {
80  int links = sequenceLinks.at(k);
81  qName += std::to_string(links) + ",";
82  }
83  qName += std::to_string(numLinks);
84  qName += "]";
85  planner->setName(qName);
86  return planner;
87 }
88 
89 int main()
90 {
91  Environment env = createHornEnvironment(numLinks, narrowPassageWidth);
92  OMPL_INFORM("Original Chain has %d links", numLinks);
93  OMPL_INFORM("Creating Horn Environment with width %f.", narrowPassageWidth);
94  envs.push_back(createHornEnvironment(1, narrowPassageWidth));
95  for (unsigned int k = 1; k < numLinks; k++)
96  {
97  envs.push_back(createHornEnvironment(k, narrowPassageWidth));
98  }
99 
100  auto chain(std::make_shared<KinematicChainSpace>(numLinks, linkLength, &env));
102 
103  ss.setStateValidityChecker(std::make_shared<KinematicChainValidityChecker>(ss.getSpaceInformation()));
104 
105  ompl::base::ScopedState<> start(chain), goal(chain);
106  std::vector<double> startVec(numLinks, boost::math::constants::pi<double>() / (double)numLinks);
107  std::vector<double> goalVec(numLinks, 0);
108  startVec[0] = 0.;
109  goalVec[0] = boost::math::constants::pi<double>() - .001;
110  chain->setup();
111  chain->copyFromReals(start.get(), startVec);
112  chain->copyFromReals(goal.get(), goalVec);
113  ss.setStartAndGoalStates(start, goal);
114 
115  double runtime_limit = 10, memory_limit = 1024;
116  int run_count = 10;
117  ompl::tools::Benchmark::Request request(runtime_limit, memory_limit, run_count, 0.5);
118  ompl::tools::Benchmark b(ss, "KinematicChain");
119  b.addExperimentParameter("num_links", "INTEGER", std::to_string(numLinks));
120 
121  //############################################################################
122  // Compare QRRT with different QuotientSpace sequences to other OMPL planner
123  //############################################################################
124  b.addPlanner(std::make_shared<ompl::geometric::STRIDE>(ss.getSpaceInformation()));
125  b.addPlanner(std::make_shared<ompl::geometric::EST>(ss.getSpaceInformation()));
126  b.addPlanner(std::make_shared<ompl::geometric::KPIECE1>(ss.getSpaceInformation()));
127  b.addPlanner(std::make_shared<ompl::geometric::RRT>(ss.getSpaceInformation()));
128  b.addPlanner(std::make_shared<ompl::geometric::PRM>(ss.getSpaceInformation()));
129 
130  b.addPlanner(GetQRRT(std::vector<unsigned int>{3}, ss.getSpaceInformation(), ss.getProblemDefinition()));
131  b.addPlanner(GetQRRT(std::vector<unsigned int>{2}, ss.getSpaceInformation(), ss.getProblemDefinition()));
132  b.addPlanner(GetQRRT(std::vector<unsigned int>{3, 5, 9}, ss.getSpaceInformation(), ss.getProblemDefinition()));
133  b.addPlanner(GetQRRT(std::vector<unsigned int>{3, 11}, ss.getSpaceInformation(), ss.getProblemDefinition()));
134  b.addPlanner(GetQRRT(std::vector<unsigned int>{10}, ss.getSpaceInformation(), ss.getProblemDefinition()));
135  b.addPlanner(GetQRRT(std::vector<unsigned int>{12}, ss.getSpaceInformation(), ss.getProblemDefinition()));
136  b.addPlanner(GetQRRT(std::vector<unsigned int>{8, 13}, ss.getSpaceInformation(), ss.getProblemDefinition()));
137  b.addPlanner(GetQRRT(std::vector<unsigned int>{}, ss.getSpaceInformation(), ss.getProblemDefinition()));
138  b.addPlanner(GetQRRT(std::vector<unsigned int>{2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14},
139  ss.getSpaceInformation(), ss.getProblemDefinition()));
140 
141  b.benchmark(request);
142  b.saveResultsToFile(boost::str(boost::format("kinematic_%i.log") % numLinks).c_str());
143 
144  printBenchmarkResults(b);
145  return 0;
146 }
Definition of a scoped state.
Definition: ScopedState.h:57
Create the set of classes typically needed to solve a geometric problem.
Definition: SimpleSetup.h:63
Benchmark a set of planners on a problem instance.
Definition: Benchmark.h:49
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68
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...
Definition: Console.cpp:120
Includes various tools such as self config, benchmarking, etc.
Representation of a benchmark request.
Definition: Benchmark.h:157