Loading...
Searching...
No Matches
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)
41 : vMax_(vMax)
42{
43 if (timeWeight < 0 || timeWeight > 1)
44 throw ompl::Exception("Error in SpaceTimeStateSpace Construction: Time weight must be between 0 and 1");
45
46 setName("SpaceTimeStateSpace" + getName());
47 addSubspace(spaceComponent, (1 - timeWeight)); // space component
48 addSubspace(std::make_shared<TimeStateSpace>(), timeWeight); // time component
49 lock();
50}
51
53{
54 double deltaSpace = distanceSpace(state1, state2);
55 double deltaTime = distanceTime(state1, state2);
56
57 if (deltaSpace / vMax_ > deltaTime + eps_)
58 return std::numeric_limits<double>::infinity();
59
60 return weights_[0] * deltaSpace + weights_[1] * deltaTime;
61}
62
63/*
64 * Direction-independent distance in space
65 */
67 const ompl::base::State *state2) const
68{
69 const auto *cstate1 = static_cast<const CompoundState *>(state1);
70 const auto *cstate2 = static_cast<const CompoundState *>(state2);
71
72 return components_[0]->distance(cstate1->components[0], cstate2->components[0]);
73}
74
75/*
76 * Direction-independent distance in time
77 */
79 const ompl::base::State *state2) const
80{
81 const auto *cstate1 = static_cast<const CompoundState *>(state1);
82 const auto *cstate2 = static_cast<const CompoundState *>(state2);
83
84 return components_[1]->distance(cstate1->components[1], cstate2->components[1]);
85}
86
88{
89 as<TimeStateSpace>(1)->setBounds(lb, ub);
90}
91
93{
94 return vMax_;
95}
96
98{
99 vMax_ = vMax;
100}
101
103 const ompl::base::State *state2) const
104{
105 double deltaSpace = distanceSpace(state1, state2);
106 return deltaSpace / vMax_;
107}
108
110{
111 return components_[0];
112}
113
118
120{
121 return false;
122}
123
125{
126 return std::numeric_limits<double>::infinity();
127}
128
130{
131 auto extent = getTimeComponent()->isBounded() ? getTimeComponent()->getMaximumExtent() :
132 getSpaceComponent()->getMaximumExtent() / vMax_;
133 eps_ = std::numeric_limits<float>::epsilon() * std::pow(10, std::ceil(std::log10(extent)));
134}
135
The exception type for ompl.
Definition Exception.h:47
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...
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
std::vector< double > weights_
The weight assigned to each component of the state space when computing the compound distance.
Definition StateSpace.h:743
std::vector< StateSpacePtr > components_
The state spaces that make up the compound state space.
Definition StateSpace.h:737
T * as(const unsigned int index) const
Cast a component of this instance to a desired type.
Definition StateSpace.h:590
Definition of a compound state.
Definition State.h:87
double getVMax() const
Maximum velocity getter.
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.
bool isMetricSpace() const override
No metric state space, as the triangle inequality is not satisfied.
TimeStateSpace * getTimeComponent()
The time component as a TimeStateSpace pointer.
void updateEpsilon()
Scale epsilon appropriately after time or space bounds were set.
double getMaximumExtent() const override
Maximum extent is infinite, as the distance can be infinite even with bounded time.
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.
double distanceTime(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the time component.
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
The distance from state1 to state2. May be infinite.
void setTimeBounds(double lb, double ub)
Set lower and upper time bounds for the time component.
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
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 ...
double vMax_
The maximum velocity of the space.
double eps_
The epsilon for time distance calculation.
void setVMax(double vMax)
Maximum velocity setter.
A shared pointer wrapper for ompl::base::StateSpace.
void setName(const std::string &name)
Set the name of the state space.
const std::string & getName() const
Get the name of the state space.
Definition of an abstract state.
Definition State.h:50
const T * as() const
Cast this instance to a desired type.
Definition State.h:66
A state space representing time. The time can be unbounded, in which case enforceBounds() is a no-op,...