From 0aacabf40fd919b1ae4d6b02b90e47eaf7c247f4 Mon Sep 17 00:00:00 2001 From: jorgenfj Date: Tue, 16 Apr 2024 13:39:47 +0200 Subject: [PATCH] flipped tf. renamed seapath --- asv_setup/launch/tf.launch.py | 36 ++++++----------------------------- 1 file changed, 6 insertions(+), 30 deletions(-) diff --git a/asv_setup/launch/tf.launch.py b/asv_setup/launch/tf.launch.py index 401c1911..476e5fbc 100644 --- a/asv_setup/launch/tf.launch.py +++ b/asv_setup/launch/tf.launch.py @@ -2,32 +2,10 @@ from launch import LaunchDescription from launch_ros.actions import Node -from rclpy.qos import QoSProfile, QoSReliabilityPolicy, QoSDurabilityPolicy, QoSHistoryPolicy -from launch.actions import ExecuteProcess def generate_launch_description(): - # command line arguments to get desired QoS settings - echo_tf_static = ExecuteProcess( - cmd=['ros2', 'topic', 'echo', '--qos-durability', 'transient_local', '--qos-reliability', 'reliable', '/tf_static'], - output='screen' - ) - - # base_link (NED) to base_link (SEU) tf. - tf_base_link_ned_to_base_link_seu = Node( - package='tf2_ros', - name='base_link_ned_to_base_link_seu', - executable='static_transform_publisher', - arguments=['--x' , '0', - '--y' , '0', - '--z' , '0', - '--roll' , '0', - '--pitch' , str(math.pi), - '--yaw' , '0', - '--frame-id' , 'base_link', - '--child-frame-id' , 'base_link_SEU'], - ) - + # base_link to os_lidar tf. tf_base_link_to_lidar = Node( package='tf2_ros', name='base_link_to_lidar', @@ -57,8 +35,8 @@ def generate_launch_description(): '--child-frame-id' , 'zed2i_camera_center'], ) - # base_link (NED) to seapath_frame (NED?) tf. - tf_base_link_ned_to_seapath_frame = Node( + # base_link (NED) to seapath_frame (NED) tf. + tf_base_link_to_seapath = Node( package='tf2_ros', name='base_link_ned_to_seapath_frame', executable='static_transform_publisher', @@ -68,14 +46,12 @@ def generate_launch_description(): '--roll' , '0', '--pitch' , '0', '--yaw' , '0', - '--frame-id' , 'base_link', - '--child-frame-id' , 'seapath_frame'], + '--frame-id' , 'seapath', + '--child-frame-id' , 'base_link'], ) return LaunchDescription([ - tf_base_link_ned_to_base_link_seu, tf_base_link_to_lidar, tf_base_link_to_zed2_camera_center, - tf_base_link_ned_to_seapath_frame, - echo_tf_static + tf_base_link_to_seapath, ])