Loading...
Searching...
No Matches
SpaceTimeStateSpace.cpp
39ompl::base::SpaceTimeStateSpace::SpaceTimeStateSpace(const StateSpacePtr& spaceComponent, double vMax,
43 throw ompl::Exception("Error in SpaceTimeStateSpace Construction: Time weight must be between 0 and 1");
51double ompl::base::SpaceTimeStateSpace::distance(const ompl::base::State *state1, const ompl::base::State *state2) const
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:1163
std::vector< double > weights_
The weight assigned to each component of the state space when computing the compound distance.
Definition StateSpace.h:741
std::vector< StateSpacePtr > components_
The state spaces that make up the compound state space.
Definition StateSpace.h:735
T * as(const unsigned int index) const
Cast a component of this instance to a desired type.
Definition StateSpace.h:590
StateSpacePtr getSpaceComponent()
The space component as a StateSpacePtr.
Definition SpaceTimeStateSpace.cpp:108
double distanceSpace(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the space component.
Definition SpaceTimeStateSpace.cpp:65
bool isMetricSpace() const override
No metric state space, as the triangle inequality is not satisfied.
Definition SpaceTimeStateSpace.cpp:118
TimeStateSpace * getTimeComponent()
The time component as a TimeStateSpace pointer.
Definition SpaceTimeStateSpace.cpp:113
void updateEpsilon()
Scale epsilon appropriately after time or space bounds were set.
Definition SpaceTimeStateSpace.cpp:128
double getMaximumExtent() const override
Maximum extent is infinite, as the distance can be infinite even with bounded time.
Definition SpaceTimeStateSpace.cpp:123
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.
Definition SpaceTimeStateSpace.cpp:101
double distanceTime(const ompl::base::State *state1, const ompl::base::State *state2) const
The distance of just the time component.
Definition SpaceTimeStateSpace.cpp:77
double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override
The distance from state1 to state2. May be infinite.
Definition SpaceTimeStateSpace.cpp:51
void setTimeBounds(double lb, double ub)
Set lower and upper time bounds for the time component.
Definition SpaceTimeStateSpace.cpp:86
static double getStateTime(const ompl::base::State *state)
The time value of the given state.
Definition SpaceTimeStateSpace.cpp:135
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 ...
Definition SpaceTimeStateSpace.cpp:39
A shared pointer wrapper for ompl::base::StateSpace.
A state space representing time. The time can be unbounded, in which case enforceBounds() is a no-op,...
Definition TimeStateSpace.h:70