11#!/usr/bin/env python3
22"""ROS2 Python launch file for interface bringup.
33
4- Dynamically computes FCU URL and TGT_SYSTEM from environment variables:
5- OFFBOARD_PORT = OFFBOARD_BASE_PORT + ROS_DOMAIN_ID
6- ONBOARD_PORT = ONBOARD_BASE_PORT + ROS_DOMAIN_ID
7- FCU_URL = udp://:<OFFBOARD_PORT>@172.31.0.200:<ONBOARD_PORT>
8- TGT_SYSTEM = 1 + ROS_DOMAIN_ID
4+ Dynamically computes FCU URL and TGT_SYSTEM from environment variables (unless FCU_URL is set):
5+ PX4: FCU_URL = udp://:<OFFBOARD_PORT>@172.31.0.200:<ONBOARD_PORT>
6+ ArduPilot SITL: FCU_URL = tcp://172.31.0.200:<5760 + ROS_DOMAIN_ID * 10>
7+ TGT_SYSTEM = 1 + ROS_DOMAIN_ID (unless TGT_SYSTEM is set)
8+
9+ FLIGHT_STACK=px4 (default) uses mavros_px4.launch.xml; FLIGHT_STACK=ardupilot uses mavros_apm.launch.xml
10+ and sets is_ardupilot on robot_interface_node.
11+
12+ map → base_link TF: ``odometry_conversion`` subscribes to ``interface_odometry_in_topic`` (default:
13+ MAVROS ``local_position/odom``), overwrites frames to map/base_link, and broadcasts TF. To drive TF
14+ from simulation ground truth instead, launch with ``interface_odometry_in_topic`` remapped to that
15+ topic (and ensure QoS/frame ids match). Other sources (VIO, etc.) can use the same remapping pattern.
916"""
1017
1118import os
1219
1320from launch import LaunchDescription
14- from launch .actions import DeclareLaunchArgument , GroupAction , IncludeLaunchDescription , OpaqueFunction
21+ from launch .actions import (
22+ DeclareLaunchArgument ,
23+ ExecuteProcess ,
24+ GroupAction ,
25+ IncludeLaunchDescription ,
26+ OpaqueFunction ,
27+ TimerAction ,
28+ )
1529from launch .launch_description_sources import AnyLaunchDescriptionSource
1630from launch_ros .actions import Node , PushRosNamespace
1731from launch_ros .substitutions import FindPackageShare
@@ -24,8 +38,16 @@ def launch_setup(context, *args, **kwargs):
2438 # Use pre-set env vars if available, otherwise compute from base ports + domain id
2539 ros_domain_id = int (os .environ .get ('ROS_DOMAIN_ID' , '0' ))
2640
41+ flight_stack = os .environ .get ('FLIGHT_STACK' , 'px4' ).strip ().lower ()
42+ is_ardupilot = flight_stack in ('ardupilot' , 'apm' )
43+
2744 if os .environ .get ('FCU_URL' ):
2845 fcu_url = os .environ ['FCU_URL' ]
46+ elif is_ardupilot :
47+ # ArduCopter SITL exposes serial0 as tcp:0.0.0.0:<5760 + ROS_DOMAIN_ID * 10>:wait
48+ # inside the Isaac container (172.31.0.200). MAVROS connects via TCP.
49+ serial0_port = 5760 + ros_domain_id * 10
50+ fcu_url = f'tcp://172.31.0.200:{ serial0_port } '
2951 else :
3052 offboard_base_port = int (os .environ .get ('OFFBOARD_BASE_PORT' , '14540' ))
3153 onboard_base_port = int (os .environ .get ('ONBOARD_BASE_PORT' , '14580' ))
@@ -48,12 +70,15 @@ def launch_setup(context, *args, **kwargs):
4870
4971 # --- MAVROS (skipped in simple sim) -------------------------------------
5072 if sim_type != 'simple' :
73+ mavros_launch = (
74+ 'mavros_apm.launch.xml' if is_ardupilot else 'mavros_px4.launch.xml'
75+ )
5176 mavros_group = GroupAction ([
5277 PushRosNamespace ('interface' ),
5378 IncludeLaunchDescription (
5479 AnyLaunchDescriptionSource ([
5580 FindPackageShare ('interface_bringup' ),
56- '/launch/mavros_px4.launch.xml ' ,
81+ f '/launch/{ mavros_launch } ' ,
5782 ]),
5883 launch_arguments = {
5984 'fcu_url' : fcu_url ,
@@ -63,6 +88,63 @@ def launch_setup(context, *args, **kwargs):
6388 ])
6489 actions .append (mavros_group )
6590
91+ # ArduPilot: MAVROS for APM on Jazzy does not auto-request MAVLink data
92+ # streams. PX4 pushes everything by default, but ArduPilot needs explicit
93+ # SET_MESSAGE_INTERVAL for each message. Without this, LOCAL_POSITION_NED
94+ # is never sent on serial0 → odometry_conversion gets nothing → no TF.
95+ # set_stream_rate (REQUEST_DATA_STREAM) does NOT reliably include
96+ # LOCAL_POSITION_NED on ArduCopter 4.x; set_message_interval works.
97+ if is_ardupilot :
98+ mavros_ns = f'/{ robot_name } /interface/mavros'
99+ odom_topic = f'/{ robot_name } /interface/mavros/local_position/odom'
100+ interval_svc = f'{ mavros_ns } /set_message_interval'
101+ # ArduPilot ACKs SET_MESSAGE_INTERVAL even before EKF converges, but
102+ # silently ignores it until the message is available. Retry in a loop
103+ # until local_position/odom actually starts publishing.
104+ # odom requires BOTH LOCAL_POSITION_NED (32) and ATTITUDE_QUATERNION (31).
105+ stream_requests = [
106+ # (MAVLink msg ID, rate Hz)
107+ (32 , 10.0 ), # LOCAL_POSITION_NED → local_position/{pose,odom}
108+ (31 , 10.0 ), # ATTITUDE_QUATERNION → attitude in odom, imu/data
109+ (30 , 10.0 ), # ATTITUDE → imu/data orientation
110+ (27 , 10.0 ), # RAW_IMU → imu/data, imu/data_raw
111+ (33 , 5.0 ), # GLOBAL_POSITION_INT → global_position/{global,rel_alt}
112+ (74 , 5.0 ), # VFR_HUD → altitude, airspeed, heading
113+ (1 , 2.0 ), # SYS_STATUS → battery, sensors health
114+ (24 , 5.0 ), # GPS_RAW_INT → GPS fix quality
115+ (29 , 2.0 ), # SCALED_PRESSURE → barometer / imu/static_pressure
116+ ]
117+ svc_calls = ' ' .join (
118+ f'ros2 service call { interval_svc } '
119+ f'mavros_msgs/srv/MessageInterval '
120+ f'"{{message_id: { mid } , message_rate: { rate } }}" > /dev/null 2>&1;'
121+ for mid , rate in stream_requests
122+ )
123+ request_script = (
124+ f'for attempt in $(seq 1 60); do '
125+ f' { svc_calls } '
126+ f' if timeout 3 ros2 topic hz { odom_topic } 2>&1 '
127+ f' | grep -q "average rate"; then '
128+ f' echo "[ArduPilot streams] local_position/odom active after attempt $attempt"; '
129+ f' exit 0; '
130+ f' fi; '
131+ f' echo "[ArduPilot streams] attempt $attempt — odom not yet active, retrying in 5s"; '
132+ f' sleep 5; '
133+ f'done; '
134+ f'echo "[ArduPilot streams] WARNING: odom still not active after 60 attempts"'
135+ )
136+ actions .append (
137+ TimerAction (
138+ period = 10.0 ,
139+ actions = [
140+ ExecuteProcess (
141+ cmd = ['bash' , '-c' , request_script ],
142+ output = 'screen' ,
143+ ),
144+ ],
145+ )
146+ )
147+
66148 # --- Interface between AirStack and MAVROS ------------------------------
67149 robot_interface_node = Node (
68150 package = 'robot_interface' ,
@@ -71,7 +153,7 @@ def launch_setup(context, *args, **kwargs):
71153 output = 'screen' ,
72154 parameters = [{
73155 'interface' : 'mavros_interface::MAVROSInterface' ,
74- 'is_ardupilot' : False ,
156+ 'is_ardupilot' : is_ardupilot ,
75157 'post_takeoff_command_delay_time' : 10.0 ,
76158 'do_global_pose_command' : False ,
77159 }],
@@ -106,6 +188,8 @@ def launch_setup(context, *args, **kwargs):
106188 namespace = 'odometry_conversion' ,
107189 output = 'screen' ,
108190 parameters = [{
191+ # True → BEST_EFFORT (MAVROS local_position/odom on Jazzy). Required for matching QoS.
192+ # False → RELIABLE (use for publishers that only offer reliable, e.g. some bag/replay setups).
109193 'odom_input_qos_is_best_effort' : True ,
110194 'new_frame_id' : 'map' ,
111195 'new_child_frame_id' : 'base_link' ,
@@ -146,7 +230,10 @@ def generate_launch_description():
146230 interface_odometry_in_topic_arg = DeclareLaunchArgument (
147231 'interface_odometry_in_topic' ,
148232 default_value = f'/{ robot_name } /interface/mavros/local_position/odom' ,
149- description = 'Input odometry topic remapped into the odometry_conversion node' ,
233+ description = (
234+ 'nav_msgs/Odometry source for odometry_conversion (map→base_link TF). '
235+ 'Default: MAVROS local position. Override for sim ground-truth or other estimators.'
236+ ),
150237 )
151238
152239 return LaunchDescription ([
0 commit comments