A Frame object that represents an orientation(quaternion) relative to a reference frame.
More...
|
FrameOrientation | changeFrameAndCopy (ReferenceFramePtr referenceFrame) const |
|
| FrameOrientation () |
|
| FrameOrientation (ReferenceFramePtr referenceFrame) |
|
| FrameOrientation (ReferenceFramePtr referenceFrame, Quaternion quat) |
|
| FrameOrientation (ReferenceFramePtr referenceFrame, double x, double y, double z, double w) |
|
| FrameOrientation (ReferenceFramePtr referenceFrame, const Matrix3d &E) |
|
| FrameOrientation (ReferenceFramePtr referenceFrame, const AxisAngle &axis_angle) |
|
| FrameOrientation (ReferenceFramePtr referenceFrame, Vector3d axis, double angle) |
|
Math::TransformableGeometricObject * | getTransformableGeometricObject () |
| Pure virtual method that FrameObjects are required to implement so the FrameObject::changeFrame method is able to access the TransformableGeometricObject which is required to implement the TransformableGeometricObject::transform method. More...
|
|
void | setIncludingFrame (const Quaternion &q, ReferenceFramePtr referenceFrame) |
|
void | setIncludingFrame (const Matrix3d &E, ReferenceFramePtr referenceFrame) |
|
void | setIncludingFrame (const AxisAngle &axis_angle, ReferenceFramePtr referenceFrame) |
|
void | setIncludingFrame (Vector3d axis, double angle, ReferenceFramePtr referenceFrame) |
|
virtual void | changeFrame (ReferenceFramePtr desiredFrame) |
| Change the ReferenceFrame this FrameObject is expressed in. More...
|
|
void | checkReferenceFramesMatch (const FrameObject *frameObject) const |
| Check if two ReferenceFrameHolders hold the same ReferenceFrame. More...
|
|
void | checkReferenceFramesMatch (FrameObject *frameObject) const |
|
| FrameObject (ReferenceFramePtr referenceFrame) |
|
ReferenceFramePtr | getReferenceFrame () const |
| Get a pointer to the reference frame this FrameObject is expressed in. More...
|
|
void | setReferenceFrame (ReferenceFramePtr frame) |
| Set frame objects internal reference frame. More...
|
|
virtual | ~FrameObject () |
| Destructor. More...
|
|
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 |
|
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) |
|
A Frame object that represents an orientation(quaternion) relative to a reference frame.
Definition at line 30 of file FrameOrientation.hpp.