Loading...
Searching...
No Matches
HybridStateSpace.cpp
47double ompl::base::HybridStateSpace::distance(const ompl::base::State *state1, const ompl::base::State *state2) const
83ompl::base::HybridTimeStateSpace *ompl::base::HybridStateSpace::getTimeComponent() // change to hybrid time
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
void lock()
Lock this state space. This means no further spaces can be added as components. This function can be ...
Definition StateSpace.cpp:1169
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
bool isMetricSpace() const override
No metric state space, as the triangle inequality is not satisfied.
Definition HybridStateSpace.cpp:88
static void setStateTime(ompl::base::State *state, double position)
Set the time position value of the given state.
Definition HybridStateSpace.cpp:108
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
Definition HybridStateSpace.cpp:98
static void setStateJumps(ompl::base::State *state, int jumps)
Set the jumps value of the given state.
Definition HybridStateSpace.cpp:113
double getMaximumExtent() const override
Maximum extent is infinite, as the distance can be infinite even with bounded time.
Definition HybridStateSpace.cpp:93
HybridTimeStateSpace * getTimeComponent()
The time component as a TimeStateSpace pointer.
Definition HybridStateSpace.cpp:83
double distanceSpace(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the space component.
Definition HybridStateSpace.cpp:57
StateSpacePtr getSpaceComponent()
The space component as a StateSpacePtr.
Definition HybridStateSpace.cpp:78
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
The distance from state1 to state2. May be infinite.
Definition HybridStateSpace.cpp:47
double distanceTime(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the time component.
Definition HybridStateSpace.cpp:69
HybridStateSpace(const StateSpacePtr &spaceComponent)
Constructor. The maximum velocity and the weight of the time component for distance calculation need ...
Definition HybridStateSpace.cpp:39
static int getStateJumps(const ompl::base::State *state)
The jumps value of the given state.
Definition HybridStateSpace.cpp:103
A state space representing time. The time can be unbounded, in which case enforceBounds() is a no-op,...
Definition HybridTimeStateSpace.h:70
A shared pointer wrapper for ompl::base::StateSpace.