mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2025-01-18 23:56:59 +00:00
update
This commit is contained in:
parent
1943de705d
commit
14c43a5567
@ -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
|
||||
################################################################################
|
||||
|
29
nodes/odom_publisher_python.py
Normal file
29
nodes/odom_publisher_python.py
Normal file
@ -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()
|
Loading…
Reference in New Issue
Block a user