Loading...
Searching...
No Matches
RigidBodyPlanning.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Rice University
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 Rice University 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: Ioan Sucan */
36
37#include <ompl/base/SpaceInformation.h>
38#include <ompl/base/spaces/SE3StateSpace.h>
39#include <ompl/geometric/planners/rrt/RRTConnect.h>
40#include <ompl/geometric/SimpleSetup.h>
41
42#include <ompl/config.h>
43#include <iostream>
44
45namespace ob = ompl::base;
46namespace og = ompl::geometric;
47
48bool isStateValid(const ob::State *state)
49{
50 // cast the abstract state type to the type we expect
51 const auto *se3state = state->as<ob::SE3StateSpace::StateType>();
52
53 // extract the first component of the state and cast it to what we expect
54 const auto *pos = se3state->as<ob::RealVectorStateSpace::StateType>(0);
55
56 // extract the second component of the state and cast it to what we expect
57 const auto *rot = se3state->as<ob::SO3StateSpace::StateType>(1);
58
59 // check validity of state defined by pos & rot
60
61 // return a value that is always true but uses the two variables we define, so we avoid compiler warnings
62 return (const void *)rot != (const void *)pos;
63}
64
65void plan()
66{
67 // construct the state space we are planning in
68 auto space(std::make_shared<ob::SE3StateSpace>());
69
70 // set the bounds for the R^3 part of SE(3)
71 ob::RealVectorBounds bounds(3);
72 bounds.setLow(-1);
73 bounds.setHigh(1);
74
75 space->setBounds(bounds);
76
77 // construct an instance of space information from this state space
78 auto si(std::make_shared<ob::SpaceInformation>(space));
79
80 // set state validity checking for this space
81 si->setStateValidityChecker(isStateValid);
82
83 // create a random start state
84 ob::ScopedState<> start(space);
85 start.random();
86
87 // create a random goal state
88 ob::ScopedState<> goal(space);
89 goal.random();
90
91 // create a problem instance
92 auto pdef(std::make_shared<ob::ProblemDefinition>(si));
93
94 // set the start and goal states
95 pdef->setStartAndGoalStates(start, goal);
96
97 // create a planner for the defined space
98 auto planner(std::make_shared<og::RRTConnect>(si));
99
100 // set the problem we are trying to solve for the planner
101 planner->setProblemDefinition(pdef);
102
103 // perform setup steps for the planner
104 planner->setup();
105
106 // print the settings for this space
107 si->printSettings(std::cout);
108
109 // print the problem settings
110 pdef->print(std::cout);
111
112 // attempt to solve the problem within one second of planning time
113 ob::PlannerStatus solved = planner->ob::Planner::solve(1.0);
114
115 if (solved)
116 {
117 // get the goal representation from the problem definition (not the same as the goal state)
118 // and inquire about the found path
119 ob::PathPtr path = pdef->getSolutionPath();
120 std::cout << "Found solution:" << std::endl;
121
122 // print the path to screen
123 path->print(std::cout);
124 }
125 else
126 std::cout << "No solution found" << std::endl;
127}
128
129void planWithSimpleSetup()
130{
131 // construct the state space we are planning in
132 auto space(std::make_shared<ob::SE3StateSpace>());
133
134 // set the bounds for the R^3 part of SE(3)
135 ob::RealVectorBounds bounds(3);
136 bounds.setLow(-1);
137 bounds.setHigh(1);
138
139 space->setBounds(bounds);
140
141 // define a simple setup class
142 og::SimpleSetup ss(space);
143
144 // set state validity checking for this space
145 ss.setStateValidityChecker([](const ob::State *state) { return isStateValid(state); });
146
147 // create a random start state
148 ob::ScopedState<> start(space);
149 start.random();
150
151 // create a random goal state
152 ob::ScopedState<> goal(space);
153 goal.random();
154
155 // set the start and goal states
156 ss.setStartAndGoalStates(start, goal);
157
158 // this call is optional, but we put it in to get more output information
159 ss.setup();
160 ss.print();
161
162 // attempt to solve the problem within one second of planning time
163 ob::PlannerStatus solved = ss.solve(1.0);
164
165 if (solved)
166 {
167 std::cout << "Found solution:" << std::endl;
168 // print the path to screen
169 ss.simplifySolution();
170 ss.getSolutionPath().print(std::cout);
171 }
172 else
173 std::cout << "No solution found" << std::endl;
174}
175
176int main(int /*argc*/, char ** /*argv*/)
177{
178 std::cout << "OMPL version: " << OMPL_VERSION << std::endl;
179
180 plan();
181
182 std::cout << std::endl << std::endl;
183
184 planWithSimpleSetup();
185
186 return 0;
187}
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.
A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w).
The definition of a state in SO(3) represented as a unit quaternion.
Definition of a scoped state.
Definition ScopedState.h:57
Definition of an abstract state.
Definition State.h:50
const T * as() const
Cast this instance to a desired type.
Definition State.h:66
Create the set of classes typically needed to solve a geometric problem.
Definition SimpleSetup.h:63
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.
A class to store the exit status of Planner::solve().