Functions
pinocchio::rpy Namespace Reference

Roll-pitch-yaw operations. More...

Functions

template<typename Vector3Like >
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::OptionscomputeRpyJacobian (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)::OptionscomputeRpyJacobianInverse (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)::OptionscomputeRpyJacobianTimeDerivative (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)::OptionsmatrixToRpy (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)::OptionsrpyToMatrix (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...
 

Detailed Description

Roll-pitch-yaw operations.

Function Documentation

◆ computeRpyJacobian()

template<typename Vector3Like >
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 $\phi = (r, p, y)$ and reference frame F (either LOCAL or WORLD), the Jacobian is such that $ {}^F\omega = J_F(\phi)\dot{\phi} $, where $ {}^F\omega $ is the angular velocity expressed in frame F and $ J_F $ is the Jacobian computed with reference frame F

Parameters
[in]rpyRoll-Pitch-Yaw vector
[in]rfReference frame in which the angular velocity is expressed
Returns
The Jacobian of the Roll-Pitch-Yaw conversion in the appropriate frame
Note
for the purpose of this function, WORLD and LOCAL_WORLD_ALIGNED are equivalent

◆ computeRpyJacobianInverse()

template<typename Vector3Like >
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 $\phi = (r, p, y)$ and reference frame F (either LOCAL or WORLD), the Jacobian is such that $ {}^F\omega = J_F(\phi)\dot{\phi} $, where $ {}^F\omega $ is the angular velocity expressed in frame F and $ J_F $ is the Jacobian computed with reference frame F

Parameters
[in]rpyRoll-Pitch-Yaw vector
[in]rfReference frame in which the angular velocity is expressed
Returns
The inverse of the Jacobian of the Roll-Pitch-Yaw conversion in the appropriate frame
Note
for the purpose of this function, WORLD and LOCAL_WORLD_ALIGNED are equivalent

◆ computeRpyJacobianTimeDerivative()

template<typename Vector3Like0 , typename Vector3Like1 >
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 $\phi = (r, p, y)$ and reference frame F (either LOCAL or WORLD), the Jacobian is such that $ {}^F\omega = J_F(\phi)\dot{\phi} $, where $ {}^F\omega $ is the angular velocity expressed in frame F and $ J_F $ is the Jacobian computed with reference frame F

Parameters
[in]rpyRoll-Pitch-Yaw vector
[in]rpydotTime derivative of the Roll-Pitch-Yaw vector
[in]rfReference frame in which the angular velocity is expressed
Returns
The time derivative of the Jacobian of the Roll-Pitch-Yaw conversion in the appropriate frame
Note
for the purpose of this function, WORLD and LOCAL_WORLD_ALIGNED are equivalent

◆ matrixToRpy()

template<typename Matrix3Like >
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 $R$, the angles $r, p, y$ are given so that $ R = R_z(y)R_y(p)R_x(r) $, where $R_{\alpha}(\theta)$ denotes the rotation of $\theta$ degrees around axis $\alpha$. The angles are guaranteed to be in the ranges $r\in[-\pi,\pi]$ $p\in[-\frac{\pi}{2},\frac{\pi}{2}]$ $y\in[-\pi,\pi]$, unlike Eigen's eulerAngles() function

Warning
the method assumes $R$ is a rotation matrix. If it is not, the result is undefined.

◆ rpyToMatrix() [1/2]

template<typename Vector3Like >
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 $(r, p, y)$, the rotation is given as $ R = R_z(y)R_y(p)R_x(r) $, where $R_{\alpha}(\theta)$ denotes the rotation of $\theta$ degrees around axis $\alpha$.

◆ rpyToMatrix() [2/2]

template<typename Scalar >
Eigen::Matrix<Scalar,3,3> pinocchio::rpy::rpyToMatrix ( const Scalar &  r,
const Scalar &  p,
const Scalar &  y 
)

Convert from Roll, Pitch, Yaw to rotation Matrix.

Given $r, p, y$, the rotation is given as $ R = R_z(y)R_y(p)R_x(r) $, where $R_{\alpha}(\theta)$ denotes the rotation of $\theta$ degrees around axis $\alpha$.



pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:02