37 #ifndef OMPL_BASE_SPACES_SO3_STATE_SPACE_
38 #define OMPL_BASE_SPACES_SO3_STATE_SPACE_
40 #include "ompl/base/StateSpace.h"
99 void setAxisAngle(
double ax,
double ay,
double az,
double angle);
138 virtual void copyState(State *destination,
const State *source)
const;
142 virtual void serialize(
void *serialization,
const State *state)
const;
144 virtual void deserialize(State *state,
const void *serialization)
const;
146 virtual double distance(
const State *state1,
const State *state2)
const;
148 virtual bool equalStates(
const State *state1,
const State *state2)
const;
150 virtual void interpolate(
const State *from,
const State *to,
const double t, State *state)
const;
156 virtual void freeState(State *state)
const;
160 virtual void printState(
const State *state, std::ostream &out)
const;
void setName(const std::string &name)
Set the name of the state space.
virtual void serialize(void *serialization, const State *state) const
Write the binary representation of state to serialization.
int type_
A type assigned for this state space.
virtual double * getValueAddressAtIndex(State *state, const unsigned int index) const
Many states contain a number of double values. This function provides a means to get the memory addre...
virtual double getMaximumExtent(void) const
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...
virtual State * allocState(void) const
Allocate a state that can store a point in the described space.
ompl::base::SO3StateSpace
virtual bool satisfiesBounds(const State *state) const
Check if a state is inside the bounding box. For unbounded spaces this function can always return tru...
virtual void printState(const State *state, std::ostream &out) const
Print a state to a stream.
virtual unsigned int getDimension(void) const
Get the dimension of the space (not the dimension of the surrounding ambient space) ...
virtual double distance(const State *state1, const State *state2) const
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
A state space representing SO(3). The internal representation is done with quaternions. The distance between states is the angle between quaternions and interpolation is done with slerp.
virtual void printSettings(std::ostream &out) const
Print the settings for this state space to a stream.
SO3StateSampler(const StateSpace *space)
Constructor.
virtual bool equalStates(const State *state1, const State *state2) const
Checks whether two states are equal.
virtual void enforceBounds(State *state) const
Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-...
State StateType
Define the type of state allocated by this space.
double w
scalar component of quaternion
virtual void deserialize(State *state, const void *serialization) const
Read the binary representation of a state from serialization and write it to state.
virtual StateSamplerPtr allocDefaultStateSampler(void) const
Allocate an instance of the default uniform state sampler for this space.
virtual void interpolate(const State *from, const State *to, const double t, State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
virtual void freeState(State *state) const
Free the memory of the allocated state.
The definition of a state in SO(3) represented as a unit quaternion.
const std::string & getName(void) const
Get the name of the state space.
State space sampler for SO(3), using quaternion representation.
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.
virtual void copyState(State *destination, const State *source) const
Copy a state to another. The memory of source and destination should NOT overlap. ...
virtual void registerProjections(void)
Register the projections for this state space. Usually, this is at least the default projection...
Definition of an abstract state.
void setAxisAngle(double ax, double ay, double az, double angle)
Set the quaternion from axis-angle representation.
virtual void sampleUniform(State *state)
Sample a state.
void setIdentity(void)
Set the state to identity – no rotation.
double z
Z component of quaternion vector.
virtual void sampleUniformNear(State *state, const State *near, const double distance)
To sample unit quaternions uniformly within some given distance, we sample a 3-vector from the R^3 ta...
Abstract definition of a state space sampler.
double y
Y component of quaternion vector.
double norm(const StateType *state) const
Compute the norm of a state.
virtual unsigned int getSerializationLength(void) const
Get the number of chars in the serialization of a state in this space.
virtual void sampleGaussian(State *state, const State *mean, const double stdDev)
Sample a state such that the expected distance between mean and state is stdDev.
double x
X component of quaternion vector.