From 8c4b4ff892af299bd02fca5dd13612c5a60e760f Mon Sep 17 00:00:00 2001 From: Lucas Walter Date: Thu, 30 May 2024 15:52:14 -0700 Subject: [PATCH] allow overriding of the tf child frame ids so multiple instances of aruco_detect won't conflict --- aruco_detect/src/aruco_detect.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/aruco_detect/src/aruco_detect.cpp b/aruco_detect/src/aruco_detect.cpp index 09da06e..14b74fe 100644 --- a/aruco_detect/src/aruco_detect.cpp +++ b/aruco_detect/src/aruco_detect.cpp @@ -95,6 +95,8 @@ class FiducialsNode { double fiducial_len; + std::string tf_prefix; + bool doPoseEstimation; bool haveCamInfo; bool publishFiducialTf; @@ -510,7 +512,7 @@ void FiducialsNode::poseEstimateCallback(const FiducialArrayConstPtr & msg) ts.transform.rotation.z = q.z(); ts.header.frame_id = frameId; ts.header.stamp = msg->header.stamp; - ts.child_frame_id = "fiducial_" + std::to_string(ids[i]); + ts.child_frame_id = tf_prefix + std::to_string(ids[i]); broadcaster.sendTransform(ts); } else { @@ -518,7 +520,7 @@ void FiducialsNode::poseEstimateCallback(const FiducialArrayConstPtr & msg) ts.transform = ft.transform; ts.header.frame_id = frameId; ts.header.stamp = msg->header.stamp; - ts.child_frame_id = "fiducial_" + std::to_string(ft.fiducial_id); + ts.child_frame_id = tf_prefix + std::to_string(ft.fiducial_id); broadcaster.sendTransform(ts); } } @@ -614,6 +616,8 @@ FiducialsNode::FiducialsNode() : nh(), pnh("~"), it(nh) pnh.param("vis_msgs", vis_msgs, false); pnh.param("verbose", verbose, false); + pnh.param("tf_prefix", tf_prefix, "fiducial_"); + std::string str; std::vector strs;