From 14c43a5567037d03198f581c7cb5362125d719d4 Mon Sep 17 00:00:00 2001 From: Your Name Date: Tue, 14 Jan 2025 09:06:55 +0100 Subject: [PATCH] update --- CMakeLists.txt | 7 +++++++ nodes/odom_publisher_python.py | 29 +++++++++++++++++++++++++++++ 2 files changed, 36 insertions(+) create mode 100644 nodes/odom_publisher_python.py diff --git a/CMakeLists.txt b/CMakeLists.txt index faa0473..84698ca 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,6 +47,13 @@ include_directories( add_executable(odom_publisher nodes/odom_publisher.cpp) target_link_libraries(odom_publisher ${catkin_LIBRARIES}) +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +catkin_install_python(PROGRAMS + nodes/odom_publisher_python.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + ################################################################################ # Install ################################################################################ diff --git a/nodes/odom_publisher_python.py b/nodes/odom_publisher_python.py new file mode 100644 index 0000000..0438f6c --- /dev/null +++ b/nodes/odom_publisher_python.py @@ -0,0 +1,29 @@ +#!/usr/bin/env python + +import rospy +from nav_msgs.msg import Odometry +import tf + +def odom_callback(msg): + # Extract position and orientation from the odometry message + position = msg.pose.pose.position + orientation = msg.pose.pose.orientation + + # Broadcast the transformation + br = tf.TransformBroadcaster() + br.sendTransform( + (position.x, position.y, position.z), # Translation + (orientation.x, orientation.y, orientation.z, orientation.w), # Rotation (quaternion) + rospy.Time.now(), # Timestamp + msg.child_frame_id if msg.child_frame_id else "base_link", # Child frame ID + msg.header.frame_id if msg.header.frame_id else "odom" # Parent frame ID + ) + +def main(): + rospy.init_node('odom_tf_publisher', anonymous=True) + rospy.Subscriber('/odom', Odometry, odom_callback) + rospy.loginfo("TF Publisher for /odom topic is running...") + rospy.spin() + +if __name__ == '__main__': + main()