Loading...
Searching...
No Matches
HybridStateSpace.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2025, University of Santa Cruz Hybrid Systems Laboratory
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 University of Santa Cruz nor the names of
18 * its 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: Beverly Xu */
36
37#include "ompl/base/spaces/HybridStateSpace.h"
38
40{
41 setName("HybridStateSpace" + getName());
42 addSubspace(spaceComponent, 1); // space component
43 addSubspace(std::make_shared<HybridTimeStateSpace>(), 1); // time component
44 lock();
45}
46
48{
49 double deltaSpace = distanceSpace(state1, state2);
50
51 return deltaSpace;
52}
53
54/*
55 * Direction-independent distance in space
56 */
58 const ompl::base::State *state2) const
59{
60 const auto *cstate1 = static_cast<const CompoundState *>(state1);
61 const auto *cstate2 = static_cast<const CompoundState *>(state2);
62
63 return components_[0]->distance(cstate1->components[0], cstate2->components[0]);
64}
65
66/*
67 * Direction-independent distance in time
68 */
70 const ompl::base::State *state2) const
71{
72 const auto *cstate1 = static_cast<const CompoundState *>(state1);
73 const auto *cstate2 = static_cast<const CompoundState *>(state2);
74
75 return components_[1]->distance(cstate1->components[1], cstate2->components[1]);
76}
77
79{
80 return components_[0];
81}
82
87
89{
90 return false;
91}
92
94{
95 return std::numeric_limits<double>::infinity();
96}
97
102
107
109{
110 state->as<CompoundState>()->as<HybridTimeStateSpace::StateType>(1)->position = position;
111}
112
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< 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
bool isMetricSpace() const override
No metric state space, as the triangle inequality is not satisfied.
static void setStateTime(ompl::base::State *state, double position)
Set the time position value of the given state.
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
static void setStateJumps(ompl::base::State *state, int jumps)
Set the jumps value of the given state.
double getMaximumExtent() const override
Maximum extent is infinite, as the distance can be infinite even with bounded time.
HybridTimeStateSpace * getTimeComponent()
The time component as a TimeStateSpace pointer.
double distanceSpace(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the space component.
StateSpacePtr getSpaceComponent()
The space component as a StateSpacePtr.
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
The distance from state1 to state2. May be infinite.
double distanceTime(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the time component.
HybridStateSpace(const StateSpacePtr &spaceComponent)
Constructor. The maximum velocity and the weight of the time component for distance calculation need ...
static int getStateJumps(const ompl::base::State *state)
The jumps value of the given state.
A state space representing time. The time can be unbounded, in which case enforceBounds() is a no-op,...
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