rpy.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2016-2020 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_math_rpy_hpp__
6 #define __pinocchio_math_rpy_hpp__
7 
8 #include "pinocchio/math/fwd.hpp"
11 
12 namespace pinocchio
13 {
14  namespace rpy
15  {
23  template<typename Scalar>
24  Eigen::Matrix<Scalar, 3, 3> rpyToMatrix(const Scalar & r, const Scalar & p, const Scalar & y);
25 
33  template<typename Vector3Like>
34  Eigen::
35  Matrix<typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options>
36  rpyToMatrix(const Eigen::MatrixBase<Vector3Like> & rpy);
37 
52  template<typename Matrix3Like>
53  Eigen::
54  Matrix<typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options>
55  matrixToRpy(const Eigen::MatrixBase<Matrix3Like> & R);
56 
72  template<typename Vector3Like>
73  Eigen::
74  Matrix<typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options>
76  const Eigen::MatrixBase<Vector3Like> & rpy, const ReferenceFrame rf = LOCAL);
77 
94  template<typename Vector3Like>
95  Eigen::
96  Matrix<typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options>
98  const Eigen::MatrixBase<Vector3Like> & rpy, const ReferenceFrame rf = LOCAL);
99 
117  template<typename Vector3Like0, typename Vector3Like1>
118  Eigen::
119  Matrix<typename Vector3Like0::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like0)::Options>
121  const Eigen::MatrixBase<Vector3Like0> & rpy,
122  const Eigen::MatrixBase<Vector3Like1> & rpydot,
123  const ReferenceFrame rf = LOCAL);
124  } // namespace rpy
125 } // namespace pinocchio
126 
127 /* --- Details -------------------------------------------------------------------- */
128 #include "pinocchio/math/rpy.hxx"
129 
130 #endif // #ifndef __pinocchio_math_rpy_hpp__
rpy
Definition: rpy.py:1
Eigen
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
pinocchio::ReferenceFrame
ReferenceFrame
Various conventions to express the velocity of a moving frame.
Definition: multibody/fwd.hpp:46
pinocchio::rpy::computeRpyJacobianTimeDerivative
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.
pinocchio::rpy::matrixToRpy
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.
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
R
R
r
FCL_REAL r
dpendulum.p
p
Definition: dpendulum.py:6
fwd.hpp
pinocchio::rpy::computeRpyJacobian
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.
comparison-operators.hpp
pinocchio::rpy::rpyToMatrix
Eigen::Matrix< Scalar, 3, 3 > rpyToMatrix(const Scalar &r, const Scalar &p, const Scalar &y)
Convert from Roll, Pitch, Yaw to rotation Matrix.
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE
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.
fwd.hpp
pinocchio::rpy::computeRpyJacobianInverse
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.
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::LOCAL
@ LOCAL
Definition: multibody/fwd.hpp:50


pinocchio
Author(s):
autogenerated on Sat Jun 1 2024 02:40:38