From 543caed2e839aeda164109cb801bd9bd0afcf0fa Mon Sep 17 00:00:00 2001 From: jgmonroy Date: Mon, 13 Mar 2017 16:26:14 +0100 Subject: [PATCH] fixed headers when publishing the TF transforms. It fixes a previous commit... -_- --- src/CLaserOdometry2D.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/CLaserOdometry2D.cpp b/src/CLaserOdometry2D.cpp index 994f85e..60e2ee5 100644 --- a/src/CLaserOdometry2D.cpp +++ b/src/CLaserOdometry2D.cpp @@ -1019,10 +1019,11 @@ void CLaserOdometry2D::PoseUpdate() //--------------------------------------- if (publish_tf) { + //ROS_INFO("[rf2o] Publishing TF: [base_link] to [odom]"); geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = ros::Time::now(); - odom_trans.header.frame_id = base_frame_id; - odom_trans.child_frame_id = odom_frame_id; + odom_trans.header.frame_id = odom_frame_id; + odom_trans.child_frame_id = base_frame_id; odom_trans.transform.translation.x = robot_pose.x(); odom_trans.transform.translation.y = robot_pose.y(); odom_trans.transform.translation.z = 0.0; @@ -1033,6 +1034,7 @@ void CLaserOdometry2D::PoseUpdate() //next, we'll publish the odometry message over ROS //------------------------------------------------- + //ROS_INFO("[rf2o] Publishing Odom Topic"); nav_msgs::Odometry odom; odom.header.stamp = ros::Time::now(); odom.header.frame_id = odom_frame_id;