Go to the documentation of this file.
   18       if (
axis.length() != 1
U)
 
   19         throw std::invalid_argument(std::string(
"Invalid axis: ").
append(
axis));
 
   22       const char axis_ = 
axis[0];
 
   35         throw std::invalid_argument(std::string(
"Invalid axis: ").
append(1
U, axis_));
 
   43       using namespace Eigen;
 
   52           static_cast<context::Matrix3s (*)(
 
   55           bp::args(
"roll", 
"pitch", 
"yaw"),
 
   56           "Given (r, p, y), the rotation is given as R = R_z(y)R_y(p)R_x(r)," 
   57           " where R_a(theta) denotes the rotation of theta radians axis a");
 
   61           static_cast<context::Matrix3s (*)(
const MatrixBase<context::Vector3s> &)
>(&
rpyToMatrix),
 
   63           "Given (r, p, y), the rotation is given as R = R_z(y)R_y(p)R_x(r)," 
   64           " where R_a(theta) denotes the rotation of theta radians axis a");
 
   70           &matrixToRpy<Eigen::Matrix3d>, bp::arg(
"R"),
 
   71           "Given a rotation matrix R, the angles (r, p, y) are given so that R = " 
   73           " where R_a(theta) denotes the rotation of theta radians axis a." 
   74           " The angles are guaranteed to be in the ranges: r in [-pi,pi]," 
   75           " p in[-pi/2,pi/2], y in [-pi,pi]");
 
   78           "rotate", &
rotate, bp::args(
"axis", 
"angle"),
 
   79           "Rotation matrix corresponding to a rotation about x, y or z" 
   80           " e.g. R = rot('x', pi / 4): rotate pi/4 rad about x axis");
 
   83           "computeRpyJacobian", &computeRpyJacobian<context::Vector3s>,
 
   84           (bp::arg(
"rpy"), bp::arg(
"reference_frame") = 
LOCAL),
 
   85           "Compute the Jacobian of the Roll-Pitch-Yaw conversion" 
   86           " Given phi = (r, p, y) such that that R = R_z(y)R_y(p)R_x(r)" 
   87           " and reference frame F (either LOCAL or WORLD)," 
   88           " the Jacobian is such that omega_F = J_F(phi)phidot," 
   89           " where omega_F is the angular velocity expressed in frame F" 
   90           " and J_F is the Jacobian computed with reference frame F" 
   92           "\trpy Roll-Pitch-Yaw vector" 
   93           "\treference_frame  Reference frame in which the angular velocity is expressed." 
   94           " Notice LOCAL_WORLD_ALIGNED is equivalent to WORLD");
 
   97           "computeRpyJacobianInverse", &computeRpyJacobianInverse<context::Vector3s>,
 
   98           (bp::arg(
"rpy"), bp::arg(
"reference_frame") = 
LOCAL),
 
   99           "Compute the inverse Jacobian of the Roll-Pitch-Yaw conversion" 
  100           " Given phi = (r, p, y) such that that R = R_z(y)R_y(p)R_x(r)" 
  101           " and reference frame F (either LOCAL or WORLD)," 
  102           " the Jacobian is such that omega_F = J_F(phi)phidot," 
  103           " where omega_F is the angular velocity expressed in frame F" 
  104           " and J_F is the Jacobian computed with reference frame F" 
  106           "\trpy Roll-Pitch-Yaw vector" 
  107           "\treference_frame  Reference frame in which the angular velocity is expressed." 
  108           " Notice LOCAL_WORLD_ALIGNED is equivalent to WORLD");
 
  111           "computeRpyJacobianTimeDerivative",
 
  112           &computeRpyJacobianTimeDerivative<context::Vector3s, context::Vector3s>,
 
  113           (bp::arg(
"rpy"), bp::arg(
"rpydot"), bp::arg(
"reference_frame") = 
LOCAL),
 
  114           "Compute the time derivative of the Jacobian of the Roll-Pitch-Yaw conversion" 
  115           " Given phi = (r, p, y) such that that R = R_z(y)R_y(p)R_x(r)" 
  116           " and reference frame F (either LOCAL or WORLD)," 
  117           " the Jacobian is such that omega_F = J_F(phi)phidot," 
  118           " where omega_F is the angular velocity expressed in frame F" 
  119           " and J_F is the Jacobian computed with reference frame F" 
  121           "\trpy Roll-Pitch-Yaw vector" 
  122           "\treference_frame  Reference frame in which the angular velocity is expressed." 
  123           " Notice LOCAL_WORLD_ALIGNED is equivalent to WORLD");
 
  
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > const Scalar & u
boost::python::object getOrCreatePythonNamespace(const std::string &submodule_name)
Helper to create or simply return an existing namespace in Python.
Roll-pitch-yaw operations.
context::Matrix3s rotate(const std::string &axis, const context::Scalar ang)
Eigen::Matrix< Scalar, 3, 3 > rpyToMatrix(const Scalar &r, const Scalar &p, const Scalar &y)
Convert from Roll, Pitch, Yaw to rotation Matrix.
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
Eigen::AngleAxis< Scalar > AngleAxis
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
Main pinocchio namespace.
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:18