From bbdb823861d2d9dfd180320d2875d2faac877371 Mon Sep 17 00:00:00 2001 From: Christian Rauch Date: Fri, 7 Jun 2024 16:56:45 +0200 Subject: [PATCH] cleanup --- src/conversion.cpp | 33 +++++++++++++-------------------- 1 file changed, 13 insertions(+), 20 deletions(-) diff --git a/src/conversion.cpp b/src/conversion.cpp index ae8fd7b..d972b8a 100644 --- a/src/conversion.cpp +++ b/src/conversion.cpp @@ -4,36 +4,35 @@ #include #include #include -#include #include template<> -void tf2::convert(const Eigen::Quaterniond& eq, geometry_msgs::msg::Quaternion& gq) +void tf2::convert(const Eigen::Quaterniond& eigen_quat, geometry_msgs::msg::Quaternion& msg_quat) { - gq.w = eq.w(); - gq.x = eq.x(); - gq.y = eq.y(); - gq.z = eq.z(); + msg_quat.w = eigen_quat.w(); + msg_quat.x = eigen_quat.x(); + msg_quat.y = eigen_quat.y(); + msg_quat.z = eigen_quat.z(); } template<> -void tf2::convert(const matd_t& mat, geometry_msgs::msg::Vector3& t) +void tf2::convert(const matd_t& mat, geometry_msgs::msg::Vector3& msg_vec) { assert(mat.nrows == 3 || mat.ncols == 3); - t.x = mat.data[0]; - t.y = mat.data[1]; - t.z = mat.data[2]; + msg_vec.x = mat.data[0]; + msg_vec.y = mat.data[1]; + msg_vec.z = mat.data[2]; } template<> -void tf2::convert(const cv::Mat_& vec, geometry_msgs::msg::Vector3& t) +void tf2::convert(const cv::Mat_& vec, geometry_msgs::msg::Vector3& msg_vec) { assert(vec.rows == 3 || vec.cols == 3); - t.x = vec.at(0); - t.y = vec.at(1); - t.z = vec.at(2); + msg_vec.x = vec.at(0); + msg_vec.y = vec.at(1); + msg_vec.z = vec.at(2); } template<> @@ -52,10 +51,6 @@ template<> geometry_msgs::msg::Transform tf2::toMsg(const std::pair, cv::Mat_>& pose) { - const cv::Quat cvq = cv::Quat::createFromRvec(pose.second); - - std::cout << "cv: " << cvq << std::endl; - assert(pose.first.rows == 3 || pose.first.cols == 3); assert(pose.second.rows == 3 || pose.second.cols == 3); @@ -63,8 +58,6 @@ tf2::toMsg(const std::pair, cv::Mat_>& pose) const Eigen::Map rvec(reinterpret_cast(pose.second.data)); const Eigen::Quaterniond q({rvec.norm(), rvec.normalized()}); - std::cout << "eigen (x,y,z,w): " << q.coeffs().transpose() << std::endl; - geometry_msgs::msg::Transform t; tf2::convert(pose.first, t.translation); tf2::convert(q, t.rotation);