rigid_transform.h 6.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194
  1. #ifndef SPACE_TRANSFORM_RIGID_TRANSFORM_H_
  2. #define SPACE_TRANSFORM_RIGID_TRANSFORM_H_
  3. #include <cmath>
  4. #include <iostream>
  5. #include <string>
  6. #include "Eigen/Core"
  7. #include "Eigen/Geometry"
  8. #include <ros/ros.h>
  9. namespace transform {
  10. template <typename FloatType>
  11. class Rigid2 {
  12. public:
  13. using Vector = Eigen::Matrix<FloatType, 2, 1>;
  14. using Rotation2D = Eigen::Rotation2D<FloatType>;
  15. Rigid2() : translation_(Vector::Zero()), rotation_(Rotation2D::Identity()) {}
  16. Rigid2(const Vector& translation, const Rotation2D& rotation)
  17. : translation_(translation), rotation_(rotation) {}
  18. Rigid2(const Vector& translation, const double rotation)
  19. : translation_(translation), rotation_(rotation) {}
  20. static Rigid2 Rotation(const double rotation) {
  21. return Rigid2(Vector::Zero(), rotation);
  22. }
  23. static Rigid2 Rotation(const Rotation2D& rotation) {
  24. return Rigid2(Vector::Zero(), rotation);
  25. }
  26. static Rigid2 Translation(const Vector& vector) {
  27. return Rigid2(vector, Rotation2D::Identity());
  28. }
  29. static Rigid2<FloatType> Identity() { return Rigid2<FloatType>(); }
  30. template <typename OtherType>
  31. Rigid2<OtherType> cast() const {
  32. return Rigid2<OtherType>(translation_.template cast<OtherType>(),
  33. rotation_.template cast<OtherType>());
  34. }
  35. const Vector& translation() const { return translation_; }
  36. Rotation2D rotation() const { return rotation_; }
  37. // double normalized_angle() const {
  38. // return common::NormalizeAngleDifference(rotation().angle());
  39. // }
  40. Rigid2 inverse() const {
  41. const Rotation2D rotation = rotation_.inverse();
  42. const Vector translation = -(rotation * translation_);
  43. return Rigid2(translation, rotation);
  44. }
  45. private:
  46. Vector translation_;
  47. Rotation2D rotation_;
  48. };
  49. template <typename FloatType>
  50. Rigid2<FloatType> operator*(const Rigid2<FloatType>& lhs,
  51. const Rigid2<FloatType>& rhs) {
  52. return Rigid2<FloatType>(
  53. lhs.rotation() * rhs.translation() + lhs.translation(),
  54. lhs.rotation() * rhs.rotation());
  55. }
  56. template <typename FloatType>
  57. typename Rigid2<FloatType>::Vector operator*(
  58. const Rigid2<FloatType>& rigid,
  59. const typename Rigid2<FloatType>::Vector& point) {
  60. return rigid.rotation() * point + rigid.translation();
  61. }
  62. // This is needed for gmock.
  63. // template <typename T>
  64. // std::ostream& operator<<(std::ostream& os,
  65. // const cartographer::transform::Rigid2<T>& rigid) {
  66. // os << rigid.DebugString();
  67. // return os;
  68. // }
  69. using Rigid2d = Rigid2<double>;
  70. using Rigid2f = Rigid2<float>;
  71. template <typename FloatType>
  72. class Rigid3 {
  73. public:
  74. using Vector = Eigen::Matrix<FloatType, 3, 1>;
  75. using Quaternion = Eigen::Quaternion<FloatType>;
  76. using AngleAxis = Eigen::AngleAxis<FloatType>;
  77. Rigid3() : translation_(Vector::Zero()), rotation_(Quaternion::Identity()) {}
  78. Rigid3(const Vector& translation, const Quaternion& rotation)
  79. : translation_(translation), rotation_(rotation) {}
  80. Rigid3(const Vector& translation, const AngleAxis& rotation)
  81. : translation_(translation), rotation_(rotation) {}
  82. static Rigid3 Rotation(const AngleAxis& angle_axis) {
  83. return Rigid3(Vector::Zero(), Quaternion(angle_axis));
  84. }
  85. static Rigid3 Rotation(const Quaternion& rotation) {
  86. return Rigid3(Vector::Zero(), rotation);
  87. }
  88. static Rigid3 Translation(const Vector& vector) {
  89. return Rigid3(vector, Quaternion::Identity());
  90. }
  91. static Rigid3 FromArrays(const std::array<FloatType, 4>& rotation,
  92. const std::array<FloatType, 3>& translation) {
  93. return Rigid3(Eigen::Map<const Vector>(translation.data()),
  94. Eigen::Quaternion<FloatType>(rotation[0], rotation[1],
  95. rotation[2], rotation[3]));
  96. }
  97. static Rigid3<FloatType> Identity() { return Rigid3<FloatType>(); }
  98. template <typename OtherType>
  99. Rigid3<OtherType> cast() const {
  100. return Rigid3<OtherType>(translation_.template cast<OtherType>(),
  101. rotation_.template cast<OtherType>());
  102. }
  103. const Vector& translation() const { return translation_; }
  104. const Quaternion& rotation() const { return rotation_; }
  105. Rigid3 inverse() const {
  106. const Quaternion rotation = rotation_.conjugate();
  107. const Vector translation = -(rotation * translation_);
  108. return Rigid3(translation, rotation);
  109. }
  110. bool IsValid() const {
  111. return !std::isnan(translation_.x()) && !std::isnan(translation_.y()) &&
  112. !std::isnan(translation_.z()) &&
  113. std::abs(FloatType(1) - rotation_.norm()) < FloatType(1e-3);
  114. }
  115. private:
  116. Vector translation_;
  117. Quaternion rotation_;
  118. };
  119. template <typename FloatType>
  120. Rigid3<FloatType> operator*(const Rigid3<FloatType>& lhs,
  121. const Rigid3<FloatType>& rhs) {
  122. return Rigid3<FloatType>(
  123. lhs.rotation() * rhs.translation() + lhs.translation(),
  124. (lhs.rotation() * rhs.rotation()).normalized());
  125. }
  126. template <typename FloatType>
  127. typename Rigid3<FloatType>::Vector operator*(
  128. const Rigid3<FloatType>& rigid,
  129. const typename Rigid3<FloatType>::Vector& point) {
  130. return rigid.rotation() * point + rigid.translation();
  131. }
  132. // This is needed for gmock.
  133. // template <typename T>
  134. // std::ostream& operator<<(std::ostream& os,
  135. // const cartographer::transform::Rigid3<T>& rigid) {
  136. // os << rigid.DebugString();
  137. // return os;
  138. // }
  139. using Rigid3d = Rigid3<double>;
  140. using Rigid3f = Rigid3<float>;
  141. // Converts (roll, pitch, yaw) to a unit length quaternion. Based on the URDF
  142. // specification http://wiki.ros.org/urdf/XML/joint.
  143. Eigen::Quaterniond RollPitchYaw(double roll, double pitch, double yaw);
  144. struct TimestampedTransform {
  145. ros::Time time;
  146. Rigid3d transform;
  147. };
  148. // Returns an transform::Rigid3d given a 'dictionary' containing 'translation'
  149. // (x, y, z) and 'rotation' which can either we an array of (roll, pitch, yaw)
  150. // or a dictionary with (w, x, y, z) values as a quaternion.
  151. // Rigid3d FromDictionary(common::LuaParameterDictionary* dictionary);
  152. } // namespace transform
  153. #endif // CARTOGRAPHER_TRANSFORM_RIGID_TRANSFORM_H_