diff --git a/CMakeLists.txt b/CMakeLists.txt index 1017960..cf2a637 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,7 +41,7 @@ find_package(image_transport REQUIRED) find_package(cv_bridge REQUIRED) find_package(Eigen3 REQUIRED NO_MODULE) find_package(Threads REQUIRED) -find_package(OpenCV REQUIRED COMPONENTS core calib3d) +find_package(OpenCV REQUIRED COMPONENTS calib3d) find_package(apriltag 3.2 REQUIRED) if(cv_bridge_VERSION VERSION_GREATER_EQUAL 3.3.0) @@ -61,6 +61,24 @@ set_property(TARGET tags PROPERTY ) +# conversion functions as template specialisation +add_library(conversion STATIC + src/conversion.cpp +) +target_link_libraries(conversion + apriltag::apriltag + Eigen3::Eigen + opencv_calib3d +) +ament_target_dependencies(conversion + geometry_msgs + tf2 +) +set_property(TARGET conversion PROPERTY + POSITION_INDEPENDENT_CODE ON +) + + # pose estimation methods add_library(pose_estimation STATIC src/pose_estimation.cpp @@ -70,9 +88,11 @@ target_link_libraries(pose_estimation Eigen3::Eigen opencv_core opencv_calib3d + conversion ) ament_target_dependencies(pose_estimation geometry_msgs + tf2 ) set_property(TARGET pose_estimation PROPERTY POSITION_INDEPENDENT_CODE ON diff --git a/src/conversion.cpp b/src/conversion.cpp new file mode 100644 index 0000000..d972b8a --- /dev/null +++ b/src/conversion.cpp @@ -0,0 +1,65 @@ +#include +#include +#include +#include +#include +#include +#include + +template<> +void tf2::convert(const Eigen::Quaterniond& eigen_quat, geometry_msgs::msg::Quaternion& msg_quat) +{ + 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& msg_vec) +{ + assert(mat.nrows == 3 || mat.ncols == 3); + + 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& msg_vec) +{ + assert(vec.rows == 3 || vec.cols == 3); + + msg_vec.x = vec.at(0); + msg_vec.y = vec.at(1); + msg_vec.z = vec.at(2); +} + +template<> +geometry_msgs::msg::Transform +tf2::toMsg(const apriltag_pose_t& pose) +{ + const Eigen::Quaterniond q(Eigen::Map>(pose.R->data)); + + geometry_msgs::msg::Transform t; + tf2::convert(*pose.t, t.translation); + tf2::convert(q, t.rotation); + return t; +} + +template<> +geometry_msgs::msg::Transform +tf2::toMsg(const std::pair, cv::Mat_>& pose) +{ + assert(pose.first.rows == 3 || pose.first.cols == 3); + assert(pose.second.rows == 3 || pose.second.cols == 3); + + // convert compact rotation vector to angle-axis to quaternion + const Eigen::Map rvec(reinterpret_cast(pose.second.data)); + const Eigen::Quaterniond q({rvec.norm(), rvec.normalized()}); + + geometry_msgs::msg::Transform t; + tf2::convert(pose.first, t.translation); + tf2::convert(q, t.rotation); + return t; +} diff --git a/src/pose_estimation.cpp b/src/pose_estimation.cpp index 979427f..e07cfbf 100644 --- a/src/pose_estimation.cpp +++ b/src/pose_estimation.cpp @@ -1,45 +1,11 @@ #include "pose_estimation.hpp" -#include +#include #include #include #include -#include +#include -geometry_msgs::msg::Transform tf_from_apriltag_pose(const apriltag_pose_t& pose) -{ - const Eigen::Quaterniond q(Eigen::Map>(pose.R->data)); - - geometry_msgs::msg::Transform t; - - t.translation.x = pose.t->data[0]; - t.translation.y = pose.t->data[1]; - t.translation.z = pose.t->data[2]; - t.rotation.w = q.w(); - t.rotation.x = q.x(); - t.rotation.y = q.y(); - t.rotation.z = q.z(); - - return t; -} - -geometry_msgs::msg::Transform tf_from_cv(const cv::Mat_& tvec, const cv::Mat_& rvec) -{ - const cv::Quat q = cv::Quat::createFromRvec(rvec); - - geometry_msgs::msg::Transform t; - - t.translation.x = tvec.at(0); - t.translation.y = tvec.at(1); - t.translation.z = tvec.at(2); - t.rotation.w = q.w; - t.rotation.x = q.x; - t.rotation.y = q.y; - t.rotation.z = q.z; - - return t; -} - geometry_msgs::msg::Transform homography(apriltag_detection_t* const detection, const std::array& intr, double tagsize) { @@ -48,7 +14,7 @@ homography(apriltag_detection_t* const detection, const std::array& i apriltag_pose_t pose; estimate_pose_for_tag_homography(&info, &pose); - return tf_from_apriltag_pose(pose); + return tf2::toMsg(const_cast(pose)); } geometry_msgs::msg::Transform @@ -77,7 +43,7 @@ pnp(apriltag_detection_t* const detection, const std::array& intr, do cv::Mat rvec, tvec; cv::solvePnP(objectPoints, imagePoints, cameraMatrix, {}, rvec, tvec); - return tf_from_cv(tvec, rvec); + return tf2::toMsg, cv::Mat_>, geometry_msgs::msg::Transform>(std::make_pair(tvec, rvec)); } const std::unordered_map pose_estimation_methods{