Go to the documentation of this file.
    5 #ifndef __pinocchio_math_rpy_hpp__ 
    6 #define __pinocchio_math_rpy_hpp__ 
   23     template<
typename Scalar>
 
   33     template<
typename Vector3Like>
 
   52     template<
typename Matrix3Like>
 
   72     template<
typename Vector3Like>
 
   94     template<
typename Vector3Like>
 
  117     template<
typename Vector3Like0, 
typename Vector3Like1>
 
  121         const 
Eigen::MatrixBase<Vector3Like0> & 
rpy,
 
  122         const 
Eigen::MatrixBase<Vector3Like1> & rpydot,
 
  128 #include "pinocchio/math/rpy.hxx" 
  130 #endif // #ifndef __pinocchio_math_rpy_hpp__ 
  
ReferenceFrame
Various conventions to express the velocity of a moving frame.
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.
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.
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.
Eigen::Matrix< Scalar, 3, 3 > rpyToMatrix(const Scalar &r, const Scalar &p, const Scalar &y)
Convert from Roll, Pitch, Yaw to rotation Matrix.
PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorType) integrate(const ModelTpl< Scalar
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
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.
Main pinocchio namespace.
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:21