Quaternion that are used for singularity free joints. More...
#include <Quaternion.h>
Public Member Functions | |
Quaternion | conjugate () const |
EIGEN_STRONG_INLINE double | getScalarPart () const |
Get scalar part. More... | |
Quaternion | operator* (const double &s) const |
Method to scale the elements of a quaternion by a constant. Normalization is NOT performed. More... | |
Quaternion | operator* (const Quaternion &q) const |
Quaternion multiplication. More... | |
Quaternion & | operator*= (const Quaternion &q) |
Overloaded *= operator for quaternion multiplication. More... | |
Quaternion & | operator= (const Eigen::Quaterniond &q) |
Quaternion & | operator= (const RobotDynamics::Math::Quaternion &q) |
Quaternion & | operator= (const Vector4d &q) |
Quaternion & | operator= (const Matrix3d &E) |
Quaternion & | operator= (const AxisAngle &axis_angle) |
Quaternion () | |
Constructor. More... | |
Quaternion (const Eigen::Quaterniond &q) | |
Quaternion (const RobotDynamics::Math::Quaternion &q) | |
Quaternion (const RobotDynamics::Math::Matrix3d &E) | |
Quaternion (const Vector4d &q) | |
Quaternion (const AxisAngle &axis_angle) | |
Quaternion (const Vector3d &axis, double angle) | |
Quaternion (double x, double y, double z, double w) | |
Constructor. More... | |
Vector3d | rotate (const Vector3d &vec) const |
void | sanitize () |
sanitize the quaternion by negating each element if the w element is less than zero More... | |
void | set (double x, double y, double z, double w) |
void | set (const Matrix3d &E) |
void | set (const Quaternion &q) |
void | set (const AxisAngle &axis_angle) |
void | set (Vector3d axis, double angle) |
Quaternion | slerp (double alpha, const Quaternion &quat) const |
From Wikipedia: In computer graphics, Slerp is shorthand for spherical linear interpolation, introduced by Ken Shoemake in the context of quaternion interpolation for the purpose of animating 3D rotation. It refers to constant-speed motion along a unit-radius great circle arc, given the ends and an interpolation parameter between 0 and 1. More... | |
void | swingTwistDecomposition (const Vector3d &twist_axis, Quaternion &swing, Quaternion &twist) |
Decompose a quaternion into a swing then twist quaternion where the twist is about the given axis. More... | |
Quaternion | timeStep (const Vector3d &omega, double dt) |
void | transform (const RobotDynamics::Math::SpatialTransform &X) |
Pure virtual object. This object forces objects that inherit from it to have a method that tells how that object is transformed. More... | |
EIGEN_STRONG_INLINE Vector3d | vec () const |
Get vector part. More... | |
EIGEN_STRONG_INLINE double & | w () |
EIGEN_STRONG_INLINE double | w () const |
EIGEN_STRONG_INLINE double & | x () |
EIGEN_STRONG_INLINE double | x () const |
EIGEN_STRONG_INLINE double & | y () |
EIGEN_STRONG_INLINE double | y () const |
EIGEN_STRONG_INLINE double & | z () |
EIGEN_STRONG_INLINE double | z () const |
Public Member Functions inherited from RobotDynamics::Math::Vector4d | |
template<typename OtherDerived > | |
Vector4d & | operator= (const Eigen::MatrixBase< OtherDerived > &other) |
void | set (const double &v0, const double &v1, const double &v2, const double &v3) |
template<typename OtherDerived > | |
Vector4d (const Eigen::MatrixBase< OtherDerived > &other) | |
EIGEN_STRONG_INLINE | Vector4d () |
EIGEN_STRONG_INLINE | Vector4d (const double &v0, const double &v1, const double &v2, const double &v3) |
Private Member Functions | |
Quaternion | fromAxisAngle (const Vector3d &axis, double angle_rad) |
Quaternion | toQuaternion (const Matrix3d &mat) |
Additional Inherited Members | |
Public Types inherited from RobotDynamics::Math::Vector4d | |
typedef Eigen::Vector4d | Base |
Quaternion that are used for singularity free joints.
order: x,y,z,w
Definition at line 25 of file Quaternion.h.
|
inline |
Constructor.
Definition at line 31 of file Quaternion.h.
|
inline |
Definition at line 36 of file Quaternion.h.
|
inline |
Definition at line 41 of file Quaternion.h.
|
inline |
Definition at line 46 of file Quaternion.h.
|
inline |
Definition at line 51 of file Quaternion.h.
|
inline |
Definition at line 56 of file Quaternion.h.
|
inline |
Definition at line 60 of file Quaternion.h.
|
inline |
|
inline |
Definition at line 285 of file Quaternion.h.
|
inlineprivate |
Definition at line 353 of file Quaternion.h.
|
inline |
|
inline |
Method to scale the elements of a quaternion by a constant. Normalization is NOT performed.
s |
Definition at line 192 of file Quaternion.h.
|
inline |
Quaternion multiplication.
q | Quaternion to multiply by |
Definition at line 202 of file Quaternion.h.
|
inline |
Overloaded *= operator for quaternion multiplication.
q | Quaternion to multiply by |
Definition at line 214 of file Quaternion.h.
|
inline |
Definition at line 141 of file Quaternion.h.
|
inline |
Definition at line 163 of file Quaternion.h.
|
inline |
Definition at line 169 of file Quaternion.h.
|
inline |
Definition at line 175 of file Quaternion.h.
|
inline |
Definition at line 181 of file Quaternion.h.
Definition at line 297 of file Quaternion.h.
|
inline |
sanitize the quaternion by negating each element if the w element is less than zero
Definition at line 150 of file Quaternion.h.
|
inline |
Definition at line 116 of file Quaternion.h.
|
inline |
Definition at line 221 of file Quaternion.h.
|
inline |
Definition at line 226 of file Quaternion.h.
|
inline |
Definition at line 231 of file Quaternion.h.
|
inline |
Definition at line 236 of file Quaternion.h.
|
inline |
From Wikipedia: In computer graphics, Slerp is shorthand for spherical linear interpolation, introduced by Ken Shoemake in the context of quaternion interpolation for the purpose of animating 3D rotation. It refers to constant-speed motion along a unit-radius great circle arc, given the ends and an interpolation parameter between 0 and 1.
alpha | Interpolation parameter. Should be between 0 and 1 |
quat | Quaternion to interpolate between |
Definition at line 258 of file Quaternion.h.
|
inline |
Decompose a quaternion into a swing then twist quaternion where the twist is about the given axis.
Definition at line 316 of file Quaternion.h.
|
inline |
Definition at line 290 of file Quaternion.h.
|
inlineprivate |
Definition at line 327 of file Quaternion.h.
|
inlinevirtual |
Pure virtual object. This object forces objects that inherit from it to have a method that tells how that object is transformed.
X | SpatialTransform |
Implements RobotDynamics::Math::TransformableGeometricObject.
Definition at line 243 of file Quaternion.h.
|
inline |
|
inline |
Definition at line 106 of file Quaternion.h.
|
inline |
Definition at line 111 of file Quaternion.h.
|
inline |
Definition at line 76 of file Quaternion.h.
|
inline |
Definition at line 81 of file Quaternion.h.
|
inline |
Definition at line 86 of file Quaternion.h.
|
inline |
Definition at line 91 of file Quaternion.h.
|
inline |
Definition at line 96 of file Quaternion.h.
|
inline |
Definition at line 101 of file Quaternion.h.