Class SO3StateSpace::StateType
Defined in File SO3StateSpace.h
Nested Relationships
This class is a nested type of Class SO3StateSpace.
Inheritance Relationships
Base Type
public ompl::base::State(Class State)
Class Documentation
-
class StateType : public ompl::base::State
The definition of a state in SO(3) represented as a unit quaternion.
Note
The order of the elements matters in this definition for the SO3StateUniformSampler::sample() function.
Public Functions
-
void setAxisAngle(double ax, double ay, double az, double angle)
Set the quaternion from axis-angle representation. The angle is given in radians.
-
void setIdentity()
Set the state to identity — no rotation.
Public Members
-
double x
X component of quaternion vector.
-
double y
Y component of quaternion vector.
-
double z
Z component of quaternion vector.
-
double w
scalar component of quaternion
-
void setAxisAngle(double ax, double ay, double az, double angle)