From 045f6a75229361e2fe82e3ad25399aa3eea40942 Mon Sep 17 00:00:00 2001 From: catskul Date: Tue, 11 Oct 2016 03:57:41 -0400 Subject: [PATCH] Pass Eigen arguments by const reference (#38) Fixes #35. --- cartographer/transform/transform.h | 28 +++++++++++++++------------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/cartographer/transform/transform.h b/cartographer/transform/transform.h index 7b8c56e..8c2ba76 100644 --- a/cartographer/transform/transform.h +++ b/cartographer/transform/transform.h @@ -51,31 +51,33 @@ T GetYaw(const Rigid3& transform) { // rotation as the given 'quaternion'. template Eigen::Matrix RotationQuaternionToAngleAxisVector( - Eigen::Quaternion quaternion) { - quaternion.normalize(); + const Eigen::Quaternion& quaternion) { + Eigen::Quaternion normalized_quaternion = quaternion.normalized(); // We choose the quaternion with positive 'w', i.e., the one with a smaller // angle that represents this orientation. - if (quaternion.w() < 0.) { + if (normalized_quaternion.w() < 0.) { // Multiply by -1. http://eigen.tuxfamily.org/bz/show_bug.cgi?id=560 - quaternion.w() *= T(-1.); - quaternion.x() *= T(-1.); - quaternion.y() *= T(-1.); - quaternion.z() *= T(-1.); + normalized_quaternion.w() *= T(-1.); + normalized_quaternion.x() *= T(-1.); + normalized_quaternion.y() *= T(-1.); + normalized_quaternion.z() *= T(-1.); } - // We convert the quaternion into a vector along the rotation axis with - // length of the rotation angle. - const T angle = T(2.) * atan2(quaternion.vec().norm(), quaternion.w()); + // We convert the normalized_quaternion into a vector along the rotation axis + // with length of the rotation angle. + const T angle = T(2.) * atan2(normalized_quaternion.vec().norm(), + normalized_quaternion.w()); constexpr double kCutoffAngle = 1e-7; // We linearize below this angle. const T scale = angle < kCutoffAngle ? T(2.) : angle / sin(angle / T(2.)); - return Eigen::Matrix(scale * quaternion.x(), scale * quaternion.y(), - scale * quaternion.z()); + return Eigen::Matrix(scale * normalized_quaternion.x(), + scale * normalized_quaternion.y(), + scale * normalized_quaternion.z()); } // Returns a quaternion representing the same rotation as the given 'angle_axis' // vector. template Eigen::Quaternion AngleAxisVectorToRotationQuaternion( - Eigen::Matrix angle_axis) { + const Eigen::Matrix& angle_axis) { T scale = T(0.5); T w = T(1.); constexpr double kCutoffAngle = 1e-8; // We linearize below this angle.