8 #ifndef __RDL_DYNAMICS_FRAME_ORIENTATION_HPP__ 9 #define __RDL_DYNAMICS_FRAME_ORIENTATION_HPP__ 106 #endif //__RDL_DYNAMICS_FRAME_ORIENTATION_HPP__ void setIncludingFrame(const Quaternion &q, ReferenceFramePtr referenceFrame)
Math::TransformableGeometricObject * getTransformableGeometricObject()
Pure virtual method that FrameObjects are required to implement so the FrameObject::changeFrame metho...
EIGEN_STRONG_INLINE double & w()
FrameOrientation(ReferenceFramePtr referenceFrame, const Matrix3d &E)
ReferenceFramePtr referenceFrame
FrameOrientation(ReferenceFramePtr referenceFrame, const AxisAngle &axis_angle)
FrameOrientation(ReferenceFramePtr referenceFrame)
void setIncludingFrame(Vector3d axis, double angle, ReferenceFramePtr referenceFrame)
std::shared_ptr< ReferenceFrame > ReferenceFramePtr
virtual void changeFrame(ReferenceFramePtr desiredFrame)
Change the ReferenceFrame this FrameObject is expressed in.
EIGEN_STRONG_INLINE double & y()
Quaternion that are used for singularity free joints.
FrameOrientation(ReferenceFramePtr referenceFrame, double x, double y, double z, double w)
FrameOrientation(ReferenceFramePtr referenceFrame, Quaternion quat)
EIGEN_STRONG_INLINE double & x()
void setIncludingFrame(const AxisAngle &axis_angle, ReferenceFramePtr referenceFrame)
EIGEN_STRONG_INLINE double & z()
FrameOrientation(ReferenceFramePtr referenceFrame, Vector3d axis, double angle)
A Frame object that represents an orientation(quaternion) relative to a reference frame...
FrameOrientation changeFrameAndCopy(ReferenceFramePtr referenceFrame) const
void setIncludingFrame(const Matrix3d &E, ReferenceFramePtr referenceFrame)
Eigen::AngleAxisd AxisAngle
An interface that objects with a ReferenceFrame extend to inherit the FrameObject::changeFrame method...
Namespace for all structures of the RobotDynamics library.