SO3StateSpace.cpp
54 static inline void computeAxisAngle(SO3StateSpace::StateType &q, double ax, double ay, double az, double angle)
71 static inline void quaternionProduct(SO3StateSpace::StateType &q, const SO3StateSpace::StateType &q0,
88 void ompl::base::SO3StateSpace::StateType::setAxisAngle(double ax, double ay, double az, double angle)
104 void ompl::base::SO3StateSampler::sampleUniformNear(State *state, const State *near, const double distance)
119 void ompl::base::SO3StateSampler::sampleGaussian(State *state, const State *mean, const double stdDev)
143 double x = rng_.gaussian(0, rotDev), y = rng_.gaussian(0, rotDev), z = rng_.gaussian(0, rotDev),
185 // see http://stackoverflow.com/questions/11667783/quaternion-and-normalization/12934750#12934750
248 Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
269 BOOST_ASSERT_MSG(satisfiesBounds(state1) && satisfiesBounds(state2), "The states passed to SO3StateSpace::distance "
287 Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
289 void ompl::base::SO3StateSpace::interpolate(const State *from, const State *to, const double t, State *state) const
371 double *ompl::base::SO3StateSpace::getValueAddressAtIndex(State *state, const unsigned int index) const
void printState(const State *state, std::ostream &out) const override
Print a state to a stream.
Definition: SO3StateSpace.cpp:376
void printSettings(std::ostream &out) const override
Print the settings for this state space to a stream.
Definition: SO3StateSpace.cpp:389
void enforceBounds(State *state) const override
Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-...
Definition: SO3StateSpace.cpp:183
double distance(const State *state1, const State *state2) const override
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
Definition: SO3StateSpace.cpp:267
Representation of a space in which planning can be performed. Topology specific sampling,...
Definition: StateSpace.h:134
double getMeasure() const override
Get a measure of the space (this can be thought of as a generalization of volume)
Definition: SO3StateSpace.cpp:171
void interpolate(const State *from, const State *to, double t, State *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
Definition: SO3StateSpace.cpp:289
void deserialize(State *state, const void *serialization) const override
Read the binary representation of a state from serialization and write it to state.
Definition: SO3StateSpace.cpp:238
The definition of a state in SO(3) represented as a unit quaternion.
Definition: SO3StateSpace.h:154
unsigned int getSerializationLength() const override
Get the number of chars in the serialization of a state in this space.
Definition: SO3StateSpace.cpp:228
double * getValueAddressAtIndex(State *state, unsigned int index) const override
Many states contain a number of double values. This function provides a means to get the memory addre...
Definition: SO3StateSpace.cpp:371
void sampleGaussian(State *state, const State *mean, double stdDev) override
Sample a state such that the expected distance between mean and state is stdDev.
Definition: SO3StateSpace.cpp:119
void registerProjections() override
Register the projections for this state space. Usually, this is at least the default projection....
Definition: SO3StateSpace.cpp:335
void freeState(State *state) const override
Free the memory of the allocated state.
Definition: SO3StateSpace.cpp:330
double getMaximumExtent() const override
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...
Definition: SO3StateSpace.cpp:166
State * allocState() const override
Allocate a state that can store a point in the described space.
Definition: SO3StateSpace.cpp:325
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...
Definition: ProjectionEvaluator.h:194
unsigned int getDimension() const override
Get the dimension of the space (not the dimension of the surrounding ambient space)
Definition: SO3StateSpace.cpp:161
void serialize(void *serialization, const State *state) const override
Write the binary representation of state to serialization.
Definition: SO3StateSpace.cpp:233
bool satisfiesBounds(const State *state) const override
Check if a state is inside the bounding box. For unbounded spaces this function can always return tru...
Definition: SO3StateSpace.cpp:213
void sampleUniformNear(State *state, const State *near, double distance) override
To sample unit quaternions uniformly within some given distance, we sample a 3-vector from the R^3 ta...
Definition: SO3StateSpace.cpp:104
bool equalStates(const State *state1, const State *state2) const override
Checks whether two states are equal.
Definition: SO3StateSpace.cpp:279
void setAxisAngle(double ax, double ay, double az, double angle)
Set the quaternion from axis-angle representation. The angle is given in radians.
Definition: SO3StateSpace.cpp:88
A shared pointer wrapper for ompl::base::StateSampler.
StateSamplerPtr allocDefaultStateSampler() const override
Allocate an instance of the default uniform state sampler for this space.
Definition: SO3StateSpace.cpp:320
double norm(const StateType *state) const
Compute the norm of a state.
Definition: SO3StateSpace.cpp:177
void copyState(State *destination, const State *source) const override
Copy a state to another. The memory of source and destination should NOT overlap.
Definition: SO3StateSpace.cpp:218