MultiLevelPlanningRigidBody2D.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 <ompl/base/spaces/SE2StateSpace.h>
39 #include <ompl/base/spaces/RealVectorStateSpace.h>
40 #include <ompl/base/SpaceInformation.h>
41 #include <ompl/base/StateSpace.h>
42 #include <ompl/multilevel/planners/qrrt/QRRT.h>
43 #include <iostream>
44 #include <boost/math/constants/constants.hpp>
45 
46 using namespace ompl::base;
47 
48 // Path Planning on fiber bundle SE2 \rightarrow R2
49 
50 bool boxConstraint(const double values[])
51 {
52  const double &x = values[0] - 0.5;
53  const double &y = values[1] - 0.5;
54  double pos_cnstr = sqrt(x * x + y * y);
55  return (pos_cnstr > 0.2);
56 }
57 bool isStateValid_SE2(const State *state)
58 {
59  const auto *SE2state = state->as<SE2StateSpace::StateType>();
60  const auto *R2 = SE2state->as<RealVectorStateSpace::StateType>(0);
61  const auto *SO2 = SE2state->as<SO2StateSpace::StateType>(1);
62  return boxConstraint(R2->values) && (SO2->value < boost::math::constants::pi<double>() / 2.0);
63 }
64 bool isStateValid_R2(const State *state)
65 {
66  const auto *R2 = state->as<RealVectorStateSpace::StateType>();
67  return boxConstraint(R2->values);
68 }
69 
70 int main()
71 {
72  // Setup SE2
73  auto SE2(std::make_shared<SE2StateSpace>());
74  RealVectorBounds bounds(2);
75  bounds.setLow(0);
76  bounds.setHigh(1);
77  SE2->setBounds(bounds);
78  SpaceInformationPtr si_SE2(std::make_shared<SpaceInformation>(SE2));
79  si_SE2->setStateValidityChecker(isStateValid_SE2);
80 
81  // Setup Quotient-Space R2
82  auto R2(std::make_shared<RealVectorStateSpace>(2));
83  R2->setBounds(0, 1);
84  SpaceInformationPtr si_R2(std::make_shared<SpaceInformation>(R2));
85  si_R2->setStateValidityChecker(isStateValid_R2);
86 
87  // Create vector of spaceinformationptr
88  std::vector<SpaceInformationPtr> si_vec;
89  si_vec.push_back(si_R2);
90  si_vec.push_back(si_SE2);
91 
92  // Define Planning Problem
93  using SE2State = ScopedState<SE2StateSpace>;
94  SE2State start_SE2(SE2);
95  SE2State goal_SE2(SE2);
96  start_SE2->setXY(0, 0);
97  start_SE2->setYaw(0);
98  goal_SE2->setXY(1, 1);
99  goal_SE2->setYaw(0);
100 
101  ProblemDefinitionPtr pdef = std::make_shared<ProblemDefinition>(si_SE2);
102  pdef->setStartAndGoalStates(start_SE2, goal_SE2);
103 
104  // Setup Planner using vector of spaceinformationptr
105  auto planner = std::make_shared<ompl::multilevel::QRRT>(si_vec);
106 
107  // Planner can be used as any other OMPL algorithm
108  planner->setProblemDefinition(pdef);
109  planner->setup();
110 
111  PlannerStatus solved = planner->Planner::solve(1.0);
112 
113  if (solved)
114  {
115  std::cout << std::string(80, '-') << std::endl;
116  std::cout << "Bundle Space Path (SE2):" << std::endl;
117  std::cout << std::string(80, '-') << std::endl;
118  pdef->getSolutionPath()->print(std::cout);
119 
120  std::cout << std::string(80, '-') << std::endl;
121  std::cout << "Base Space Path (R2) :" << std::endl;
122  std::cout << std::string(80, '-') << std::endl;
123  const ProblemDefinitionPtr pdefR2 = planner->getProblemDefinition(0);
124  pdefR2->getSolutionPath()->print(std::cout);
125  std::cout << std::string(80, '-') << std::endl;
126  }
127  return 0;
128 }
A shared pointer wrapper for ompl::control::SpaceInformation.
Definition of an abstract state.
Definition: State.h:113
This namespace contains sampling based planning routines shared by both planning under geometric cons...
const T * as() const
Cast this instance to a desired type.
Definition: State.h:162
A class to store the exit status of Planner::solve()
A shared pointer wrapper for ompl::base::ProblemDefinition.
The definition of a state in SO(2)
A state in SE(2): (x, y, yaw)
Definition of a scoped state.
Definition: ScopedState.h:120
The lower and upper bounds for an Rn space.