Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

flipped tf. renamed seapath #178

Merged
merged 1 commit into from
Apr 16, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
36 changes: 6 additions & 30 deletions asv_setup/launch/tf.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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',
Expand Down Expand Up @@ -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',
Expand All @@ -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,
])
Loading