Loading...
Searching...
No Matches
SpaceTimePlanning.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2021, Technische Universität Berlin (TU Berlin)
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 TU Berlin 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: Francesco Grothe */
36
37#include <ompl/base/SpaceInformation.h>
38#include <ompl/base/spaces/SpaceTimeStateSpace.h>
39#include <ompl/geometric/planners/rrt/RRTConnect.h>
40#include <ompl/geometric/planners/rrt/STRRTstar.h>
41#include <ompl/geometric/SimpleSetup.h>
42
43#include <ompl/config.h>
44#include <iostream>
45
46namespace ob = ompl::base;
47namespace og = ompl::geometric;
48
52
53bool isStateValid(const ob::State *state)
54{
55 // extract the space component of the state and cast it to what we expect
56 const auto pos = state->as<ob::CompoundState>()->as<ob::RealVectorStateSpace::StateType>(0)->values[0];
57
58 // extract the time component of the state and cast it to what we expect
59 const auto t = state->as<ob::CompoundState>()->as<ob::TimeStateSpace::StateType>(1)->position;
60
61 // check validity of state defined by pos & t (e.g. check if constraints are satisfied)...
62
63 // return a value that is always true
64 return t >= 0 && pos < std::numeric_limits<double>::infinity();
65}
66
67class SpaceTimeMotionValidator : public ob::MotionValidator
68{
69public:
70 explicit SpaceTimeMotionValidator(const ob::SpaceInformationPtr &si)
71 : MotionValidator(si)
72 , vMax_(si_->getStateSpace().get()->as<ob::SpaceTimeStateSpace>()->getVMax())
73 , stateSpace_(si_->getStateSpace().get()) {};
74
75 bool checkMotion(const ob::State *s1, const ob::State *s2) const override
76 {
77 // assume motion starts in a valid configuration, so s1 is valid
78 if (!si_->isValid(s2))
79 {
80 invalid_++;
81 return false;
82 }
83
84 // check if motion is forward in time and is not exceeding the speed limit
85 auto *space = stateSpace_->as<ob::SpaceTimeStateSpace>();
86 auto deltaPos = space->distanceSpace(s1, s2);
87 auto deltaT = s2->as<ob::CompoundState>()->as<ob::TimeStateSpace::StateType>(1)->position -
88 s1->as<ob::CompoundState>()->as<ob::TimeStateSpace::StateType>(1)->position;
89
90 if (!(deltaT > 0 && deltaPos / deltaT <= vMax_))
91 {
92 invalid_++;
93 return false;
94 }
95
96 // check if the path between the states is unconstrained (perform interpolation)...
97
98 return true;
99 }
100
101 bool checkMotion(const ompl::base::State *, const ompl::base::State *,
102 std::pair<ob::State *, double> &) const override
103 {
104 throw ompl::Exception("SpaceTimeMotionValidator::checkMotion", "not implemented");
105 }
106
107private:
108 double vMax_; // maximum velocity
109 ob::StateSpace *stateSpace_; // the animation state space for distance calculation
110};
111
112void plan(void)
113{
114 // set maximum velocity
115 double vMax = 0.2;
116
117 // construct the state space we are planning in
118 auto vectorSpace(std::make_shared<ob::RealVectorStateSpace>(1));
119 auto space = std::make_shared<ob::SpaceTimeStateSpace>(vectorSpace, vMax);
120
121 // set the bounds for R1
122 ob::RealVectorBounds bounds(1);
123 bounds.setLow(-1.0);
124 bounds.setHigh(1.0);
125 vectorSpace->setBounds(bounds);
126
127 // set time bounds. Planning with unbounded time is also possible when using ST-RRT*.
128 space->setTimeBounds(0.0, 10.0);
129
130 // create the space information class for the space
131 ob::SpaceInformationPtr si = std::make_shared<ob::SpaceInformation>(space);
132
133 // set state validity checking for this space
134 si->setStateValidityChecker([](const ob::State *state) { return isStateValid(state); });
135 si->setMotionValidator(std::make_shared<SpaceTimeMotionValidator>(si));
136
137 // define a simple setup class
138 og::SimpleSetup ss(si);
139
140 // create a start state
141 ob::ScopedState<> start(space);
142 start[0] = 0; // pos
143
144 // create a goal state
145 ob::ScopedState<> goal(space);
146 goal[0] = 1; // pos
147
148 // set the start and goal states
149 ss.setStartAndGoalStates(start, goal);
150
151 // construct the planner
152 auto *strrtStar = new og::STRRTstar(si);
153
154 // set planner parameters
155 strrtStar->setRange(vMax);
156
157 // set the used planner
158 ss.setPlanner(ob::PlannerPtr(strrtStar));
159
160 // attempt to solve the problem within one second of planning time
161 ob::PlannerStatus solved = ss.solve(1.0);
162
163 if (solved)
164 {
165 std::cout << "Found solution:" << std::endl;
166 // print the path to screen
167 ss.getSolutionPath().print(std::cout);
168 }
169 else
170 std::cout << "No solution found" << std::endl;
171}
172
173int main(int /*argc*/, char ** /*argv*/)
174{
175 std::cout << "OMPL version: " << OMPL_VERSION << std::endl;
176
177 plan();
178
179 return 0;
180}
Definition of a compound state.
Definition State.h:87
Abstract definition for a class checking the validity of motions – path segments between states....
MotionValidator(SpaceInformation *si)
Constructor.
SpaceInformation * si_
The instance of space information this state validity checker operates on.
unsigned int invalid_
Number of invalid segments.
The lower and upper bounds for an Rn space.
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
Space-Time RRT* (STRRTstar).
Definition STRRTstar.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().