Utilities for arithmetic on quaternions.
|
template<typename Scalar > |
Eigen::Quaternion< Scalar > | ClosestQuaternion (const Eigen::Quaternion< Scalar > &quat1, const Eigen::Quaternion< Scalar > &quat2) |
| Returns a unit quaternion that represents the same orientation as quat2 , and has the "shortest" geodesic distance on the unit sphere to quat1 . More...
|
|
template<typename Derived > |
Vector4< typename Derived::Scalar > | quatConjugate (const Eigen::MatrixBase< Derived > &q) |
|
template<typename Derived1 , typename Derived2 > |
Vector4< typename Derived1::Scalar > | quatProduct (const Eigen::MatrixBase< Derived1 > &q1, const Eigen::MatrixBase< Derived2 > &q2) |
|
template<typename DerivedQ , typename DerivedV > |
Vector3< typename DerivedV::Scalar > | quatRotateVec (const Eigen::MatrixBase< DerivedQ > &q, const Eigen::MatrixBase< DerivedV > &v) |
|
template<typename Derived1 , typename Derived2 > |
Vector4< typename Derived1::Scalar > | quatDiff (const Eigen::MatrixBase< Derived1 > &q1, const Eigen::MatrixBase< Derived2 > &q2) |
|
template<typename Derived1 , typename Derived2 , typename DerivedU > |
Derived1::Scalar | quatDiffAxisInvar (const Eigen::MatrixBase< Derived1 > &q1, const Eigen::MatrixBase< Derived2 > &q2, const Eigen::MatrixBase< DerivedU > &u) |
|
template<typename T > |
boolean< T > | is_quaternion_in_canonical_form (const Eigen::Quaternion< T > &quat) |
| This function tests whether a quaternion is in "canonical form" meaning that it tests whether the quaternion [w, x, y, z] has a non-negative w value. More...
|
|
template<typename T > |
Eigen::Quaternion< T > | QuaternionToCanonicalForm (const Eigen::Quaternion< T > &quat) |
| This function returns a quaternion in its "canonical form" meaning that it returns a quaternion [w, x, y, z] with a non-negative w. More...
|
|
template<typename T > |
boolean< T > | AreQuaternionsEqualForOrientation (const Eigen::Quaternion< T > &quat1, const Eigen::Quaternion< T > &quat2, const T tolerance) |
| This function tests whether two quaternions represent the same orientation. More...
|
|
template<typename T > |
Vector4< T > | CalculateQuaternionDtFromAngularVelocityExpressedInB (const Eigen::Quaternion< T > &quat_AB, const Vector3< T > &w_AB_B) |
| This function calculates a quaternion's time-derivative from its quaternion and angular velocity. More...
|
|
template<typename T > |
Vector3< T > | CalculateAngularVelocityExpressedInBFromQuaternionDt (const Eigen::Quaternion< T > &quat_AB, const Vector4< T > &quatDt) |
| This function calculates angular velocity from a quaternion and its time- derivative. More...
|
|
template<typename T > |
T | CalculateQuaternionDtConstraintViolation (const Eigen::Quaternion< T > &quat, const Vector4< T > &quatDt) |
| This function calculates how well a quaternion and its time-derivative satisfy the quaternion time-derivative constraint specified in [Kane, 1983] Section 1.13, equations 12-13, page 59. More...
|
|
template<typename T > |
boolean< T > | IsQuaternionValid (const Eigen::Quaternion< T > &quat, const double tolerance) |
| This function tests if a quaternion satisfies the quaternion constraint specified in [Kane, 1983] Section 1.3, equation 4, page 12, i.e., a quaternion [w, x, y, z] must satisfy: w^2 + x^2 + y^2 + z^2 = 1. More...
|
|
template<typename T > |
boolean< T > | IsBothQuaternionAndQuaternionDtOK (const Eigen::Quaternion< T > &quat, const Vector4< T > &quatDt, const double tolerance) |
| This function tests if a quaternion satisfies the time-derivative constraint specified in [Kane, 1983] Section 1.13, equation 13, page 59. More...
|
|
template<typename T > |
bool | IsQuaternionAndQuaternionDtEqualAngularVelocityExpressedInB (const Eigen::Quaternion< T > &quat, const Vector4< T > &quatDt, const Vector3< T > &w_B, const double tolerance) |
| This function tests if a quaternion and a quaternion's time derivative can calculate and match an angular velocity to within a tolerance. More...
|
|