SpaceTimeStateSpace.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/spaces/SpaceTimeStateSpace.h"
38 
40  double timeWeight) : vMax_(vMax)
41 {
42  if (timeWeight < 0 || timeWeight > 1)
43  throw ompl::Exception("Error in SpaceTimeStateSpace Construction: Time weight must be between 0 and 1");
44 
45  setName("SpaceTimeStateSpace" + getName());
46  addSubspace(spaceComponent, (1 - timeWeight)); // space component
47  addSubspace(std::make_shared<TimeStateSpace>(), timeWeight); // time component
48  lock();
49 }
50 
52 {
53  double deltaSpace = distanceSpace(state1, state2);
54  double deltaTime = distanceTime(state1, state2);
55 
56  if (deltaSpace / vMax_ > deltaTime + eps_) return std::numeric_limits<double>::infinity();
57 
58  return weights_[0] * deltaSpace + weights_[1] * deltaTime;
59 
60 }
61 
62 /*
63  * Direction-independent distance in space
64  */
66  const ompl::base::State *state2) const
67 {
68  const auto *cstate1 = static_cast<const CompoundState *>(state1);
69  const auto *cstate2 = static_cast<const CompoundState *>(state2);
70 
71  return components_[0]->distance(cstate1->components[0], cstate2->components[0]);
72 }
73 
74 /*
75  * Direction-independent distance in time
76  */
78  const ompl::base::State *state2) const
79 {
80  const auto *cstate1 = static_cast<const CompoundState *>(state1);
81  const auto *cstate2 = static_cast<const CompoundState *>(state2);
82 
83  return components_[1]->distance(cstate1->components[1], cstate2->components[1]);
84 }
85 
87 {
88  as<TimeStateSpace>(1)->setBounds(lb, ub);
89 }
90 
92 {
93  return vMax_;
94 }
95 
97 {
98  vMax_ = vMax;
99 }
100 
102  const ompl::base::State *state2) const
103 {
104  double deltaSpace = distanceSpace(state1, state2);
105  return deltaSpace / vMax_;
106 }
107 
109 {
110  return components_[0];
111 }
112 
114 {
115  return components_[1]->as<TimeStateSpace>();
116 }
117 
119 {
120  return false;
121 }
122 
124 {
125  return std::numeric_limits<double>::infinity();
126 }
127 
129 {
130  auto extent = getTimeComponent()->isBounded() ? getTimeComponent()->getMaximumExtent() :
131  getSpaceComponent()->getMaximumExtent() / vMax_;
132  eps_ = std::numeric_limits<float>::epsilon() * std::pow(10, std::ceil(std::log10(extent)));
133 }
134 
136 {
137  return state->as<CompoundState>()->as<TimeStateSpace::StateType>(1)->position;
138 }
double getMaximumExtent() const override
Maximum extent is infinite, as the distance can be infinite even with bounded time.
Definition of a compound state.
Definition: State.h:150
void updateEpsilon()
Scale epsilon appropriately after time or space bounds were set.
A state space representing time. The time can be unbounded, in which case enforceBounds() is a no-op,...
Definition of an abstract state.
Definition: State.h:113
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
The distance from state1 to state2. May be infinite.
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
void setTimeBounds(double lb, double ub)
Set lower and upper time bounds for the time component.
const T * as() const
Cast this instance to a desired type.
Definition: State.h:162
TimeStateSpace * getTimeComponent()
The time component as a TimeStateSpace pointer.
double timeToCoverDistance(const ompl::base::State *state1, const ompl::base::State *state2) const
The time to get from state1 to state2 with respect to vMax.
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
bool isMetricSpace() const override
No metric state space, as the triangle inequality is not satisfied.
SpaceTimeStateSpace(const StateSpacePtr &spaceComponent, double vMax=1.0, double timeWeight=0.5)
Constructor. The maximum velocity and the weight of the time component for distance calculation need ...
const std::string & getName() const
Get the name of the state space.
Definition: StateSpace.cpp:196
void setVMax(double vMax)
Maximum velocity setter.
void setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:201
T * as()
Cast this instance to a desired type.
Definition: StateSpace.h:151
A shared pointer wrapper for ompl::base::StateSpace.
double distanceTime(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the time component.
void addSubspace(const StateSpacePtr &component, double weight)
Adds a new state space as part of the compound state space. For computing distances within the compou...
Definition: StateSpace.cpp:871
double getVMax() const
Maximum velocity getter.
The exception type for ompl.
Definition: Exception.h:78
StateSpacePtr getSpaceComponent()
The space component as a StateSpacePtr.
double distanceSpace(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the space component.