From edb23af234c074581eedc309998b155e658d1b5c Mon Sep 17 00:00:00 2001 From: Your Name Date: Tue, 14 Jan 2025 12:40:08 +0100 Subject: [PATCH] update --- nodes/odom_publisher_linus.py | 75 +++++++++++++---------------------- 1 file changed, 28 insertions(+), 47 deletions(-) diff --git a/nodes/odom_publisher_linus.py b/nodes/odom_publisher_linus.py index d8bc51d..2d99dd3 100644 --- a/nodes/odom_publisher_linus.py +++ b/nodes/odom_publisher_linus.py @@ -1,57 +1,38 @@ -#include -#include -#include -#include -#include +#!/usr/bin/env python -volatile sig_atomic_t flag = 0; +import rospy +from tf.transform_broadcaster import TransformBroadcaster +from nav_msgs.msg import Odometry +from geometry_msgs.msg import TransformStamped -void signal_handler(int signum) { - flag = 1; -} +def odom_callback(msg): + # Create TransformStamped message + odom_trans = TransformStamped() + odom_trans.header.stamp = msg.header.stamp + odom_trans.header.frame_id = msg.header.frame_id + odom_trans.child_frame_id = msg.child_frame_id -void odomCallback(const nav_msgs::Odometry::ConstPtr& msg, tf::TransformBroadcaster& odom_broadcaster) { - // Create transform message - geometry_msgs::TransformStamped odom_trans; - odom_trans.header.stamp = msg->header.stamp; - odom_trans.header.frame_id = msg->header.frame_id; - odom_trans.child_frame_id = msg->child_frame_id; + # Set translation + odom_trans.transform.translation.x = msg.pose.pose.position.x + odom_trans.transform.translation.y = msg.pose.pose.position.y + odom_trans.transform.translation.z = msg.pose.pose.position.z - // Copy translation and rotation - odom_trans.transform.translation.x = msg->pose.pose.position.x; - odom_trans.transform.translation.y = msg->pose.pose.position.y; - odom_trans.transform.translation.z = msg->pose.pose.position.z; - odom_trans.transform.rotation = msg->pose.pose.orientation; + # Set rotation + odom_trans.transform.rotation = msg.pose.pose.orientation - // Publish the transform - odom_broadcaster.sendTransform(odom_trans); -} + # Broadcast the transform + tf_broadcaster.sendTransformMessage(odom_trans) -int main(int argc, char** argv) { - ros::init(argc, argv, "tf_broadcaster"); - ros::NodeHandle nh; +if __name__ == "__main__": + rospy.init_node("tf_broadcaster") - // Register the signal handler - signal(SIGINT, signal_handler); + # Create a TransformBroadcaster + tf_broadcaster = TransformBroadcaster() - // Create the transform broadcaster - tf::TransformBroadcaster odom_broadcaster; + # Subscribe to the /odom topic + rospy.Subscriber("/odom", Odometry, odom_callback) - // Subscribe to the /odom topic - ros::Subscriber odom_sub = nh.subscribe( - "/odom", 10, - boost::bind(odomCallback, _1, boost::ref(odom_broadcaster))); + rospy.loginfo("TF broadcaster node is running...") - ROS_INFO("TF broadcaster node running..."); - - // Spin until the node is stopped - ros::Rate rate(10.0); // Adjust rate if necessary - while (ros::ok() && !flag) { - ros::spinOnce(); - rate.sleep(); - } - - ROS_INFO("TF broadcaster node shutting down."); - ros::shutdown(); - return 0; -} + # Keep the node running + rospy.spin()