Namespaces | Functions
rpy.hpp File Reference
#include "pinocchio/math/fwd.hpp"
#include "pinocchio/math/comparison-operators.hpp"
#include "pinocchio/multibody/fwd.hpp"
#include "pinocchio/math/rpy.hxx"
Include dependency graph for rpy.hpp:

Go to the source code of this file.

Namespaces

 pinocchio
 Main pinocchio namespace.
 
 pinocchio::rpy
 Roll-pitch-yaw operations.
 

Functions

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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:05