Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef CARTOGRAPHER_TRANSFORM_TRANSFORM_H_
00018 #define CARTOGRAPHER_TRANSFORM_TRANSFORM_H_
00019
00020 #include <cmath>
00021
00022 #include "Eigen/Core"
00023 #include "Eigen/Geometry"
00024 #include "cartographer/common/math.h"
00025 #include "cartographer/transform/proto/transform.pb.h"
00026 #include "cartographer/transform/rigid_transform.h"
00027
00028 namespace cartographer {
00029 namespace transform {
00030
00031
00032
00033 template <typename FloatType>
00034 FloatType GetAngle(const Rigid3<FloatType>& transform) {
00035 return FloatType(2) * std::atan2(transform.rotation().vec().norm(),
00036 std::abs(transform.rotation().w()));
00037 }
00038
00039
00040
00041
00042 template <typename T>
00043 T GetYaw(const Eigen::Quaternion<T>& rotation) {
00044 const Eigen::Matrix<T, 3, 1> direction =
00045 rotation * Eigen::Matrix<T, 3, 1>::UnitX();
00046 return atan2(direction.y(), direction.x());
00047 }
00048
00049
00050
00051 template <typename T>
00052 T GetYaw(const Rigid3<T>& transform) {
00053 return GetYaw(transform.rotation());
00054 }
00055
00056
00057
00058
00059 template <typename T>
00060 Eigen::Matrix<T, 3, 1> RotationQuaternionToAngleAxisVector(
00061 const Eigen::Quaternion<T>& quaternion) {
00062 Eigen::Quaternion<T> normalized_quaternion = quaternion.normalized();
00063
00064
00065 if (normalized_quaternion.w() < 0.) {
00066
00067 normalized_quaternion.w() = -1. * normalized_quaternion.w();
00068 normalized_quaternion.x() = -1. * normalized_quaternion.x();
00069 normalized_quaternion.y() = -1. * normalized_quaternion.y();
00070 normalized_quaternion.z() = -1. * normalized_quaternion.z();
00071 }
00072
00073
00074 const T angle =
00075 2. * atan2(normalized_quaternion.vec().norm(), normalized_quaternion.w());
00076 constexpr double kCutoffAngle = 1e-7;
00077 const T scale = angle < kCutoffAngle ? T(2.) : angle / sin(angle / 2.);
00078 return Eigen::Matrix<T, 3, 1>(scale * normalized_quaternion.x(),
00079 scale * normalized_quaternion.y(),
00080 scale * normalized_quaternion.z());
00081 }
00082
00083
00084
00085 template <typename T>
00086 Eigen::Quaternion<T> AngleAxisVectorToRotationQuaternion(
00087 const Eigen::Matrix<T, 3, 1>& angle_axis) {
00088 T scale = T(0.5);
00089 T w = T(1.);
00090 constexpr double kCutoffAngle = 1e-8;
00091 if (angle_axis.squaredNorm() > kCutoffAngle) {
00092 const T norm = angle_axis.norm();
00093 scale = sin(norm / 2.) / norm;
00094 w = cos(norm / 2.);
00095 }
00096 const Eigen::Matrix<T, 3, 1> quaternion_xyz = scale * angle_axis;
00097 return Eigen::Quaternion<T>(w, quaternion_xyz.x(), quaternion_xyz.y(),
00098 quaternion_xyz.z());
00099 }
00100
00101
00102 template <typename T>
00103 Rigid2<T> Project2D(const Rigid3<T>& transform) {
00104 return Rigid2<T>(transform.translation().template head<2>(),
00105 GetYaw(transform));
00106 }
00107
00108
00109 template <typename T>
00110 Rigid3<T> Embed3D(const Rigid2<T>& transform) {
00111 return Rigid3<T>(
00112 {transform.translation().x(), transform.translation().y(), T(0)},
00113 Eigen::AngleAxis<T>(transform.rotation().angle(),
00114 Eigen::Matrix<T, 3, 1>::UnitZ()));
00115 }
00116
00117
00118 Rigid2d ToRigid2(const proto::Rigid2d& transform);
00119 Eigen::Vector2d ToEigen(const proto::Vector2d& vector);
00120 Eigen::Vector3f ToEigen(const proto::Vector3f& vector);
00121 Eigen::Vector4f ToEigen(const proto::Vector4f& vector);
00122 Eigen::Vector3d ToEigen(const proto::Vector3d& vector);
00123 Eigen::Quaterniond ToEigen(const proto::Quaterniond& quaternion);
00124 proto::Rigid2d ToProto(const Rigid2d& transform);
00125 proto::Rigid2f ToProto(const Rigid2f& transform);
00126 proto::Rigid3d ToProto(const Rigid3d& rigid);
00127 Rigid3d ToRigid3(const proto::Rigid3d& rigid);
00128 proto::Rigid3f ToProto(const Rigid3f& rigid);
00129 proto::Vector2d ToProto(const Eigen::Vector2d& vector);
00130 proto::Vector3f ToProto(const Eigen::Vector3f& vector);
00131 proto::Vector4f ToProto(const Eigen::Vector4f& vector);
00132 proto::Vector3d ToProto(const Eigen::Vector3d& vector);
00133 proto::Quaternionf ToProto(const Eigen::Quaternionf& quaternion);
00134 proto::Quaterniond ToProto(const Eigen::Quaterniond& quaternion);
00135
00136 }
00137 }
00138
00139 #endif // CARTOGRAPHER_TRANSFORM_TRANSFORM_H_