Loading...
Searching...
No Matches
HybridStateSpace.h
63 double distance(const ompl::base::State *state1, const ompl::base::State *state2) const override;
66 double timeToCoverDistance(const ompl::base::State *state1, const ompl::base::State *state2) const;
bool isMetricSpace() const override
No metric state space, as the triangle inequality is not satisfied.
Definition HybridStateSpace.cpp:88
void updateEpsilon()
Scale epsilon appropriately after time or space bounds were set.
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
void setTimeBounds(double lb, double ub)
Set lower and upper time bounds for the time component.
double timeToCoverDistance(const ompl::base::State *state1, const ompl::base::State *state2) const
The time to get from state1 to state2.
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.
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66