From 73e3a354659c4454d487727299323ec090409ca0 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 25 Feb 2017 14:56:50 -0500 Subject: [PATCH] TF fixes. --- src/CLaserOdometry2D.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/CLaserOdometry2D.cpp b/src/CLaserOdometry2D.cpp index 7f6e0fb..c06446f 100644 --- a/src/CLaserOdometry2D.cpp +++ b/src/CLaserOdometry2D.cpp @@ -80,7 +80,7 @@ void CLaserOdometry2D::Init() tf::StampedTransform transform; try { - tf_listener.lookupTransform("/base_link", last_scan.header.frame_id, ros::Time(0), transform); + tf_listener.lookupTransform(base_frame_id, last_scan.header.frame_id, ros::Time(0), transform); } catch (tf::TransformException &ex) { @@ -918,7 +918,7 @@ void CLaserOdometry2D::PoseUpdate() tf::StampedTransform transform; try { - tf_listener.lookupTransform(last_scan.header.frame_id, "/base_link", ros::Time(0), transform); + tf_listener.lookupTransform(last_scan.header.frame_id, base_frame_id, ros::Time(0), transform); } catch (tf::TransformException &ex) { @@ -978,8 +978,8 @@ void CLaserOdometry2D::PoseUpdate() //--------------------------------------- geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = ros::Time::now(); - odom_trans.header.frame_id = odom_frame_id; - odom_trans.child_frame_id = base_frame_id; + odom_trans.header.frame_id = base_frame_id; + odom_trans.child_frame_id = odom_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;