Class UnitQuaternion#
Defined in File UnitQuaternion.h
Class Documentation#
-
class UnitQuaternion#
Class for unit quaternions attitude representations.
Unit quaternion class
See the Pose representations section for more discussion on attitude representations.
Public Functions
-
UnitQuaternion(double x, double y, double z, double w, bool renormalize = false, bool skip_values_check = false)#
Constructor from 4 scalar coefficients.
The input 4 values are ordered to contain the vector values first, followed by the scalar value.
- Parameters:
x – the first element of the vector part
y – the second element of the vector part
z – the third element of the vector part
w – the scalar element
renormalize – if true, normalize the input values
skip_values_check – if true, skip check that the quaternion is unit norm
-
UnitQuaternion(const Quaterniond &q, bool renormalize = false, bool skip_values_check = false)#
Constructor from a Eigen::Quaterniond input.
Note that the Eigen class is for general quaternions, not just unit quaternions. So we need to turn on checks by default.
- Parameters:
q – Eigen Quaterniond.
renormalize – if true, normalize the input values
skip_values_check – if true, skip check that the quaternion is unit norm
-
UnitQuaternion(const RotationVector &rv)#
Constructor from a RotationVector.
- Parameters:
rv – RotationVector to create this UnitQuaternion from.
-
UnitQuaternion(const Vec4 &v, bool renormalize = false, bool skip_values_check = false)#
Constructor from a 4-vector of coefficients.
The input 4-vector is assumed to contain the vector values first, followed by the scalar value.
- Parameters:
v – the 4-vector input
renormalize – if true, normalize the input values
skip_values_check – if true, skip check that the quaternion is unit norm
-
UnitQuaternion(const Eigen::AngleAxis<double> &aa)#
Constructor from angle/axis representation.
Note that angle/axis representation must be a valid one with a normalized vector for the axis component. Since the AngleAxis class does not guarantee this, we have to enable checks by default.
- Parameters:
aa – the angle/axis input
-
UnitQuaternion(const Vec3 &v1, const Vec3 &v2)#
Constructor from pair of to/from 3-vectors.
Compute the quaternion to transform one vector to another one. The normalized versions of the vectors are used, the input vectors do not have to be unit norm. Assuming the input vectors are unit norm, then we will have: v2 = quat * v1.
- Parameters:
v1 – The ‘from’ vector
v2 – The ‘to’ vector
-
UnitQuaternion(const RotationMatrix &rot)#
Constructor from a rotation matrix.
- Parameters:
rot – Input rotation matrix
-
template<typename euler_system>
inline UnitQuaternion(const EulerAngles<double, euler_system> &ea)# Constructor from EulerAngles.
- Parameters:
ea – Euler angles to construct this UnitQuaternion from.
-
std::string_view typeString() const#
Get the type string of this class.
- Returns:
“UnitQuaternion”
-
std::string dumpString(std::string_view prefix = "", unsigned int precision = 10, bool exponential = false) const#
Get a string representation of the UnitQuaternion.
- Parameters:
prefix – String prefix for each line.
precision – Number of digits to use for floating point values.
exponential – Use exponential notation if true.
- Returns:
String with information about this UnitQuaternion.
-
void dump(std::string_view prefix = "", unsigned int precision = 10, bool exponential = false) const#
Print dumpString to std::cout.
- Parameters:
prefix – String prefix for each line.
precision – Number of digits to use for floating point values.
exponential – Use exponential notation if true.
-
void uninitialize()#
Mark this UnitQuaternion as uninitialized.
-
bool isInitialized() const#
Check whether this UnitQuaternion is initialized.
- Returns:
True if initialized, false otherwise.
-
UnitQuaternion(const UnitQuaternion &other)#
Copy constructor.
- Parameters:
other – The other quaternion to copy from.
-
UnitQuaternion(UnitQuaternion &&other) noexcept#
Move constructor.
- Parameters:
other – The other quaternion to move from.
-
UnitQuaternion &operator=(const UnitQuaternion &other)#
Copy assignment operator.
- Parameters:
other – UnitQuaternion to copy from.
- Returns:
Reference to this object.
-
UnitQuaternion &operator=(UnitQuaternion &&other) noexcept#
Move assignment operator.
- Parameters:
other – UnitQuaternion to move from.
- Returns:
Reference to this object.
-
const Quaterniond &asEigen() const#
Return the native Eigen representation for the quaternion.
- Returns:
the Quaterniond representation
-
const RotationMatrix &toRotationMatrix() const#
Return the rotation matrix for this quaternion.
The rotation matrix is recomputed if the current value is stale, else the cached value is returned.
- Returns:
The rotation matrix representation of this UnitQuaternion.
-
template<typename euler_system>
inline EulerAngles<double, euler_system> toEulerAngles()# Convert to EulerAngles with the specified EulerSystem.
- Returns:
EulerAngles for this quaternion.
-
bool isIdentity(double epsilon = MATH_EPSILON) const#
Check whether this quaternion is the identity quaterion.
- Parameters:
epsilon – the tolerance value
- Returns:
true, if the quaternion is the identity quaternion; false otherwise.
-
void setIdentity()#
Set the unit quaternion to the identity value
-
bool operator==(const UnitQuaternion &other) const#
Check whether this quaternion is exactly the same as another.
- Parameters:
other – the other quaternion
- Returns:
true, if the quaternions are the same
-
bool isApprox(const UnitQuaternion &other, double prec = MATH_EPSILON) const#
Check whether this quaternion is approximately the same as another.
This method will also return true if the coefficients are approximately negative of all the coefficients of the other (since both unit quaternions then represent the same rotation).
- Parameters:
other – the other quaternion
prec – the tolerance value
- Returns:
true, if the quaternions are the same within the specfied tolerance
-
UnitQuaternion operator*(const UnitQuaternion &other) const#
Product with another quaterion.
- Parameters:
other – the other quaternion
- Returns:
The resulting quaternion from the product
-
Vec3 operator*(const Vec3 &vec) const#
Rotate the input 3-vector.
- Parameters:
vec – 3-vector to transform
- Returns:
Transformed vector
-
SpatialVector operator*(const SpatialVector &vec) const#
Rotate the input spatial vector.
- Parameters:
vec – spatial vector to transform
- Returns:
Transformed vector
-
UnitQuaternion inverse() const#
Return the inverse of the quaternion.
- Returns:
the inverse quaternion
-
const Eigen::Ref<const Vec3> vec() const#
Return the 3-vector part of the quaternion coefficients.
- Returns:
3-vector coefficients.
-
Eigen::AngleAxis<double> toAngleAxis() const#
Return the angle/axis representation for the quaternion.
- Returns:
angle/axis representation
-
RotationVector toRotationVector() const#
Return the RotationVector representation for the quaternion.
- Returns:
RotationVector representation
-
const Vec4 &toVector4() const#
Return the quaternion elements as a 4-vector.
Note that the vector elements are in the beginning, and the last element is the scalar.
- Returns:
4-vector of coefficients.
-
Mat33 rotate(const Mat33 &mat) const#
Apply a rotational transformation symmetrically to a 3x3 matrix.
Multiply the input 3x3 matrix from the left by R, and the right by R transpose: R * M * R_T. Here, R denotes the 3x3 rotation matrix for this quaternion.
See also
inverseRotate66()
- Parameters:
mat – 3x3 matrix to transform
- Returns:
Transformed matrix
-
Mat6n rotateLeft6N(const Mat6n &mat) const#
Apply a rotational transformation from the left to a 6xN matrix.
Multiply the input 6xN matrix from the left as (R_block_diag) * M. Here, R_block_diag denotes a 6x6 matrix containing the 3x3 rotation matrix for this quaternion repeated along the block diagonal.
See also
- Parameters:
mat – 6xN matrix to transform
- Returns:
Transformed matrix
-
Mat rotateRightN6(const Mat &mat) const#
Apply a rotational transformation from the right to a Nx6 matrix.
Multiply the input Nx6 matrix from the right as M * (R_block_diag). Here, R_block_diag denotes a 6x6 matrix containing the 3x3 rotation matrix for this quaternion repeated along the block diagonal.
See also
- Parameters:
mat – Nx6 matrix to transform
- Returns:
Transformed matrix
-
Mat66 rotate66(const Mat66 &mat) const#
Apply a rotational transformation symmetrically to a 6x6 matrix.
Multiply the input 6x6 matrix from both sides by (R_block_diag) * M * (R_block_diag)_T. Here, R_block_diag denotes a 6x6 matrix containing the 3x3 rotation matrix for this quaternion repeated along the block diagonal.
See also
inverseRotate66()
- Parameters:
mat – 6x6 matrix to transform
- Returns:
Transformed matrix
-
Vec4 omegaToRates(const Vec3 &omega, bool oframe) const#
Compute the quaternion coeff rates for an angular velocity.
See also
quatVecDot2omegaMap(), omega2quatVecDotMap(), omega2quat0DotMap()
- Parameters:
omega – the input angular velocity
oframe – if true, the angular velocity is in the ‘from’ frame, else the ‘to’ frame
- Returns:
the 4-vector with coefficient rates
-
Mat33 vectorRatesToOmegaMap(bool oframe, double epsilon = MATH_EPSILON) const#
The 3x3 matrix that maps the quaternion vector rates to the angular velocity.
See also
quatVecDot2omegaMap(), omega2quatVecDotMap(), omega2quat0DotMap()
- Parameters:
oframe – if true, the angular velocity is in the ‘from’ frame, else the ‘to’ frame
epsilon – tolerance to check if close to 180 degree rotation
- Returns:
the 3x3 matrix map
-
Mat33 omegaToVectorRatesMap(bool oframe) const#
The 3x3 matrix that maps the angular velocity to the quaternion vector rates.
See also
quatVecDot2omegaMap(), omega2quatVecDotMap(), omega2quat0DotMap()
- Parameters:
oframe – if true, the angular velocity is in the ‘from’ frame, else in the ‘to’ frame
- Returns:
the 3x3 matrix map
-
Vec3 omegaToScalarRateMap() const#
The 3-vecor whose dot product with the angular velocity yeilds the scalar coeff rates.
This expression is the same whether the angular velocity is in the oframe or not
See also
quatVecDot2omegaMap(), omega2quatVecDotMap(), omega2quat0DotMap()
- Returns:
the 3 vector map
-
Mat ratesToOmegaMap(bool oframe) const#
The 3x4 matrix that maps the coefficient rates to the angular velocity.
- Parameters:
oframe – if true, the angular velocity is in the ‘from’ frame, else the ‘to’ frame.
- Returns:
the 3x4 matrix map
-
UnitQuaternion(double x, double y, double z, double w, bool renormalize = false, bool skip_values_check = false)#