Roll-pitch-yaw operations. More...
| Functions | |
| template<typename Vector3Like > | |
| Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | computeRpyJacobian (const Eigen::MatrixBase< Vector3Like > &rpy, const ReferenceFrame rf=LOCAL) | 
| Compute the Jacobian of the Roll-Pitch-Yaw conversion.  More... | |
| template<typename Vector3Like > | |
| Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | computeRpyJacobianInverse (const Eigen::MatrixBase< Vector3Like > &rpy, const ReferenceFrame rf=LOCAL) | 
| Compute the inverse Jacobian of the Roll-Pitch-Yaw conversion.  More... | |
| template<typename Vector3Like0 , typename Vector3Like1 > | |
| Eigen::Matrix< typename Vector3Like0::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like0)::Options > | computeRpyJacobianTimeDerivative (const Eigen::MatrixBase< Vector3Like0 > &rpy, const Eigen::MatrixBase< Vector3Like1 > &rpydot, const ReferenceFrame rf=LOCAL) | 
| Compute the time derivative Jacobian of the Roll-Pitch-Yaw conversion.  More... | |
| template<typename Matrix3Like > | |
| Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > | matrixToRpy (const Eigen::MatrixBase< Matrix3Like > &R) | 
| Convert from Transformation Matrix to Roll, Pitch, Yaw.  More... | |
| template<typename Vector3Like > | |
| Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > | rpyToMatrix (const Eigen::MatrixBase< Vector3Like > &rpy) | 
| Convert from Roll, Pitch, Yaw to rotation Matrix.  More... | |
| template<typename Scalar > | |
| Eigen::Matrix< Scalar, 3, 3 > | rpyToMatrix (const Scalar &r, const Scalar &p, const Scalar &y) | 
| Convert from Roll, Pitch, Yaw to rotation Matrix.  More... | |
Roll-pitch-yaw operations.
| Eigen:: Matrix<typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options> pinocchio::rpy::computeRpyJacobian | ( | const Eigen::MatrixBase< Vector3Like > & | rpy, | 
| const ReferenceFrame | rf = LOCAL | ||
| ) | 
Compute the Jacobian of the Roll-Pitch-Yaw conversion.
Given  and reference frame F (either LOCAL or WORLD), the Jacobian is such that
 and reference frame F (either LOCAL or WORLD), the Jacobian is such that  , where
, where  is the angular velocity expressed in frame F and
 is the angular velocity expressed in frame F and  is the Jacobian computed with reference frame F
 is the Jacobian computed with reference frame F
| [in] | rpy | Roll-Pitch-Yaw vector | 
| [in] | rf | Reference frame in which the angular velocity is expressed | 
| Eigen:: Matrix<typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options> pinocchio::rpy::computeRpyJacobianInverse | ( | const Eigen::MatrixBase< Vector3Like > & | rpy, | 
| const ReferenceFrame | rf = LOCAL | ||
| ) | 
Compute the inverse Jacobian of the Roll-Pitch-Yaw conversion.
Given  and reference frame F (either LOCAL or WORLD), the Jacobian is such that
 and reference frame F (either LOCAL or WORLD), the Jacobian is such that  , where
, where  is the angular velocity expressed in frame F and
 is the angular velocity expressed in frame F and  is the Jacobian computed with reference frame F
 is the Jacobian computed with reference frame F
| [in] | rpy | Roll-Pitch-Yaw vector | 
| [in] | rf | Reference frame in which the angular velocity is expressed | 
| Eigen:: Matrix<typename Vector3Like0::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like0)::Options> pinocchio::rpy::computeRpyJacobianTimeDerivative | ( | const Eigen::MatrixBase< Vector3Like0 > & | rpy, | 
| const Eigen::MatrixBase< Vector3Like1 > & | rpydot, | ||
| const ReferenceFrame | rf = LOCAL | ||
| ) | 
Compute the time derivative Jacobian of the Roll-Pitch-Yaw conversion.
Given  and reference frame F (either LOCAL or WORLD), the Jacobian is such that
 and reference frame F (either LOCAL or WORLD), the Jacobian is such that  , where
, where  is the angular velocity expressed in frame F and
 is the angular velocity expressed in frame F and  is the Jacobian computed with reference frame F
 is the Jacobian computed with reference frame F
| [in] | rpy | Roll-Pitch-Yaw vector | 
| [in] | rpydot | Time derivative of the Roll-Pitch-Yaw vector | 
| [in] | rf | Reference frame in which the angular velocity is expressed | 
| Eigen:: Matrix<typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> pinocchio::rpy::matrixToRpy | ( | const Eigen::MatrixBase< Matrix3Like > & | R | ) | 
Convert from Transformation Matrix to Roll, Pitch, Yaw.
Given a rotation matrix  , the angles
, the angles  are given so that
 are given so that  , where
, where  denotes the rotation of
 denotes the rotation of  degrees around axis
 degrees around axis  . The angles are guaranteed to be in the ranges
. The angles are guaranteed to be in the ranges ![$r\in[-\pi,\pi]$](form_101.png) 
 ![$p\in[-\frac{\pi}{2},\frac{\pi}{2}]$](form_102.png) 
 ![$y\in[-\pi,\pi]$](form_103.png) , unlike Eigen's eulerAngles() function
, unlike Eigen's eulerAngles() function
 is a rotation matrix. If it is not, the result is undefined.
 is a rotation matrix. If it is not, the result is undefined. | Eigen:: Matrix<typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options> pinocchio::rpy::rpyToMatrix | ( | const Eigen::MatrixBase< Vector3Like > & | rpy | ) | 
Convert from Roll, Pitch, Yaw to rotation Matrix.
Given a vector  , the rotation is given as
, the rotation is given as  , where
, where  denotes the rotation of
 denotes the rotation of  degrees around axis
 degrees around axis  .
.