From d29ba4b80dfed238ff63382289b6802315ad5bcb Mon Sep 17 00:00:00 2001 From: daviddudas <david.dudas@outlook.com> Date: Sun, 18 Oct 2020 15:34:43 +0200 Subject: [PATCH] Add a switch to disable publish TF --- nodes/mecanum_drive_odometry | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/nodes/mecanum_drive_odometry b/nodes/mecanum_drive_odometry index 10623a7..a43e748 100755 --- a/nodes/mecanum_drive_odometry +++ b/nodes/mecanum_drive_odometry @@ -52,6 +52,7 @@ class OdometryNode: self.odomFrameID = rospy.get_param('~odom_frame_id', 'odom') self.encoderMin = int(rospy.get_param('~encoder_min', -32768)) self.encoderMax = int(rospy.get_param('~encoder_max', 32767)) + self.publishTF = rospy.get_param('~publish_tf', 'true') self.odometry.setWheelSeparation(self.wheelSeparation) self.odometry.setWheelSeparationLength(self.wheelSeparationLength) @@ -70,13 +71,16 @@ class OdometryNode: pose = self.odometry.getPose() q = quaternion_from_euler(0, 0, pose.theta) - self.tfPub.sendTransform( - (pose.x, pose.y, 0), - (q[0], q[1], q[2], q[3]), - now, - self.baseFrameID, - self.odomFrameID - ) + + if self.publishTF == 'true': + self.tfPub.sendTransform( + (pose.x, pose.y, 0), + (q[0], q[1], q[2], q[3]), + now, + self.baseFrameID, + self.odomFrameID + ) + odom = Odometry() odom.header.stamp = now -- GitLab