SpaceTimeStateSpace.h
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 #ifndef OMPL_BASE_SPACES_ANIMATION_STATE_SPACE_
38 #define OMPL_BASE_SPACES_ANIMATION_STATE_SPACE_
39 
40 #include "ompl/base/StateSpace.h"
41 #include <ompl/base/spaces/RealVectorStateSpace.h>
42 #include <ompl/base/spaces/TimeStateSpace.h>
43 #include <ompl/util/Exception.h>
44 
45 namespace ompl
46 {
47  namespace base
48  {
50  class SpaceTimeStateSpace : public CompoundStateSpace
51  {
52  public:
55  explicit SpaceTimeStateSpace(const StateSpacePtr& spaceComponent, double vMax = 1.0, double timeWeight = 0.5);
56 
63  double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override;
64 
66  double timeToCoverDistance(const ompl::base::State *state1, const ompl::base::State *state2) const;
67 
69  double distanceSpace(const ompl::base::State *state1, const ompl::base::State *state2) const;
70 
72  double distanceTime(const ompl::base::State *state1, const ompl::base::State *state2) const;
73 
75  static double getStateTime(const ompl::base::State *state) ;
76 
78  void setTimeBounds(double lb, double ub);
79 
81  double getVMax() const;
82 
84  void setVMax(double vMax);
85 
88 
90  TimeStateSpace * getTimeComponent();
91 
93  bool isMetricSpace() const override;
94 
96  double getMaximumExtent() const override;
97 
99  void updateEpsilon();
100 
101  protected:
103  double vMax_;
104 
106  double eps_ = std::numeric_limits<float>::epsilon();
107  };
108  }
109 }
110 
111 #endif
double getMaximumExtent() const override
Maximum extent is infinite, as the distance can be infinite even with bounded time.
double eps_
The epsilon for time distance calculation.
void updateEpsilon()
Scale epsilon appropriately after time or space bounds were set.
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 setTimeBounds(double lb, double ub)
Set lower and upper time bounds for the time component.
double vMax_
The maximum velocity of the space.
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 ...
void setVMax(double vMax)
Maximum velocity setter.
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.
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.
Main namespace. Contains everything in this library.
Definition: AppBase.h:21