rpy_utils.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2019 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
7 #include <mc_rtc/pragma.h>
8 
9 #include <SpaceVecAlg/SpaceVecAlg>
10 
11 namespace mc_rbdyn
12 {
13 
25 inline Eigen::Matrix3d rpyToMat(const double & r, const double & p, const double & y)
26 {
27  MC_RTC_diagnostic_push
28  MC_RTC_diagnostic_ignored(GCC, "-Wconversion")
29  return sva::RotX(r) * sva::RotY(p) * sva::RotZ(y);
30  MC_RTC_diagnostic_pop
31 }
32 
40 inline Eigen::Matrix3d rpyToMat(const Eigen::Vector3d & rpy)
41 {
42  return rpyToMat(rpy(0), rpy(1), rpy(2));
43 }
44 
52 inline sva::PTransformd rpyToPT(const Eigen::Vector3d & rpy)
53 {
54  return sva::PTransformd(rpyToMat(rpy(0), rpy(1), rpy(2)));
55 }
56 
68 inline sva::PTransformd rpyToPT(const double & r, const double & p, const double & y)
69 {
70  return sva::PTransformd(rpyToMat(r, p, y));
71 }
72 
83 inline Eigen::Vector3d rpyFromMat(const Eigen::Matrix3d & E)
84 {
85  double roll = atan2(E(1, 2), E(2, 2));
86  double pitch = -asin(E(0, 2));
87  double yaw = atan2(E(0, 1), E(0, 0));
88  return Eigen::Vector3d(roll, pitch, yaw);
89 }
90 
103 inline Eigen::Vector3d rpyFromQuat(const Eigen::Quaterniond & quat)
104 {
105  return rpyFromMat(quat.toRotationMatrix());
106 }
107 
109 template<typename T>
110 Eigen::Vector3d rpyFromRotation(const T & value)
111 {
112  if constexpr(std::is_same_v<T, Eigen::Quaterniond>) { return rpyFromQuat(value); }
113  else { return rpyFromMat(value); }
114 }
115 
116 } // namespace mc_rbdyn
pragma.h
MC_RTC_diagnostic_ignored
MC_RTC_diagnostic_push MC_RTC_diagnostic_ignored(GCC, "-Wsign-conversion") MC_RTC_diagnostic_pop namespace sch
Definition: surface_hull.h:11
mc_rbdyn::rpyFromQuat
Eigen::Vector3d rpyFromQuat(const Eigen::Quaterniond &quat)
Definition: rpy_utils.h:103
mc_rbdyn::rpyFromRotation
Eigen::Vector3d rpyFromRotation(const T &value)
Definition: rpy_utils.h:110
mc_rbdyn::rpyFromMat
Eigen::Vector3d rpyFromMat(const Eigen::Matrix3d &E)
Definition: rpy_utils.h:83
mc_rbdyn::rpyToPT
sva::PTransformd rpyToPT(const Eigen::Vector3d &rpy)
Definition: rpy_utils.h:52
mc_rbdyn
Definition: generic_gripper.h:14
mc_rbdyn::rpyToMat
Eigen::Matrix3d rpyToMat(const double &r, const double &p, const double &y)
Definition: rpy_utils.h:25