cps_rmp220_support/nodes/odom_publisher_python.py

44 lines
1.3 KiB
Python
Raw Normal View History

2025-01-14 08:06:55 +00:00
#!/usr/bin/env python
import rospy
from nav_msgs.msg import Odometry
import tf
2025-01-14 08:30:25 +00:00
import math
def normalize_quaternion(x, y, z, w):
norm = math.sqrt(x**2 + y**2 + z**2 + w**2)
return x / norm, y / norm, z / norm, w / norm
2025-01-14 08:06:55 +00:00
def odom_callback(msg):
# Extract position and orientation from the odometry message
position = msg.pose.pose.position
orientation = msg.pose.pose.orientation
2025-01-14 08:30:25 +00:00
# Normalize the quaternion
qx, qy, qz, qw = normalize_quaternion(
orientation.x, orientation.y, orientation.z, orientation.w
)
2025-01-14 08:35:16 +00:00
# Get frame IDs from the message
2025-01-14 10:53:14 +00:00
parent_frame_id = msg.header.frame_id if msg.header.frame_id else "Odometry"
2025-01-14 08:35:16 +00:00
child_frame_id = msg.child_frame_id if msg.child_frame_id else "base_link"
2025-01-14 08:06:55 +00:00
# Broadcast the transformation
br = tf.TransformBroadcaster()
br.sendTransform(
(position.x, position.y, position.z), # Translation
2025-01-14 08:30:25 +00:00
(qx, qy, qz, qw), # Normalized rotation (quaternion)
2025-01-14 08:06:55 +00:00
rospy.Time.now(), # Timestamp
2025-01-14 08:35:16 +00:00
child_frame_id, # Child frame ID
parent_frame_id # Parent frame ID
2025-01-14 08:06:55 +00:00
)
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()