17 #ifndef CARTOGRAPHER_TRANSFORM_TRANSFORM_H_ 18 #define CARTOGRAPHER_TRANSFORM_TRANSFORM_H_ 23 #include "Eigen/Geometry" 25 #include "cartographer/transform/proto/transform.pb.h" 33 template <
typename FloatType>
43 T
GetYaw(
const Eigen::Quaternion<T>& rotation) {
44 const Eigen::Matrix<T, 3, 1> direction =
45 rotation * Eigen::Matrix<T, 3, 1>::UnitX();
46 return atan2(direction.y(), direction.x());
61 const Eigen::Quaternion<T>& quaternion) {
62 Eigen::Quaternion<T> normalized_quaternion = quaternion.normalized();
65 if (normalized_quaternion.w() < 0.) {
67 normalized_quaternion.w() *= T(-1.);
68 normalized_quaternion.x() *= T(-1.);
69 normalized_quaternion.y() *= T(-1.);
70 normalized_quaternion.z() *= T(-1.);
74 const T
angle = T(2.) *
atan2(normalized_quaternion.vec().norm(),
75 normalized_quaternion.w());
76 constexpr
double kCutoffAngle = 1e-7;
77 const T scale = angle < kCutoffAngle ? T(2.) : angle / sin(angle / T(2.));
78 return Eigen::Matrix<T, 3, 1>(scale * normalized_quaternion.x(),
79 scale * normalized_quaternion.y(),
80 scale * normalized_quaternion.z());
87 const Eigen::Matrix<T, 3, 1>& angle_axis) {
90 constexpr
double kCutoffAngle = 1e-8;
91 if (angle_axis.squaredNorm() > kCutoffAngle) {
92 const T norm = angle_axis.norm();
93 scale = sin(norm / 2.) / norm;
96 const Eigen::Matrix<T, 3, 1> quaternion_xyz = scale * angle_axis;
97 return Eigen::Quaternion<T>(w, quaternion_xyz.x(), quaternion_xyz.y(),
102 template <
typename T>
109 template <
typename T>
113 Eigen::AngleAxis<T>(transform.
rotation().angle(),
114 Eigen::Matrix<T, 3, 1>::UnitZ()));
119 Eigen::Vector2d
ToEigen(
const proto::Vector2d& vector);
120 Eigen::Vector3f
ToEigen(
const proto::Vector3f& vector);
121 Eigen::Vector3d
ToEigen(
const proto::Vector3d& vector);
122 Eigen::Quaterniond
ToEigen(
const proto::Quaterniond& quaternion);
128 proto::Vector2d
ToProto(
const Eigen::Vector2d& vector);
129 proto::Vector3f
ToProto(
const Eigen::Vector3f& vector);
130 proto::Vector3d
ToProto(
const Eigen::Vector3d& vector);
131 proto::Quaternionf
ToProto(
const Eigen::Quaternionf& quaternion);
132 proto::Quaterniond
ToProto(
const Eigen::Quaterniond& quaternion);
137 #endif // CARTOGRAPHER_TRANSFORM_TRANSFORM_H_
T atan2(const Eigen::Matrix< T, 2, 1 > &vector)