Skip to content

Commit 512f866

Browse files
author
Docs Deploy
committed
Deployed 5ab7dc6 to main with MkDocs 1.6.1 and mike 2.1.4
1 parent 77c7e63 commit 512f866

File tree

14 files changed

+665
-127
lines changed

14 files changed

+665
-127
lines changed

main/docs/simulation/isaac_sim/index.html

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5134,6 +5134,13 @@ <h2 id="usd-file-naming-conventions">USD File Naming Conventions<a class="header
51345134
<p><code>*.scene.usd</code> ⟵ an environment PLUS physics, simulation, or robots</p>
51355135
</li>
51365136
</ul>
5137+
<h2 id="pegasus-launch-scripts-isaac_sim_script_name">Pegasus launch scripts (<code>ISAAC_SIM_SCRIPT_NAME</code>)<a class="headerlink" href="#pegasus-launch-scripts-isaac_sim_script_name" title="Permanent link">&para;</a></h2>
5138+
<p>Set <code>ISAAC_SIM_SCRIPT_NAME</code> in the repo <code>.env</code> to one of the Python files under <code>simulation/isaac-sim/launch_scripts/</code>:</p>
5139+
<ul>
5140+
<li><code>example_one_px4_pegasus_launch_script.py</code> / <code>example_two_px4_pegasus_launch_script.py</code> — PX4 SITL + Pegasus</li>
5141+
<li><code>example_one_ardupilot_pegasus_launch_script.py</code> / <code>example_two_ardupilot_pegasus_launch_script.py</code> — ArduPilot SITL + Pegasus</li>
5142+
</ul>
5143+
<p>For ArduPilot in Docker/headless Isaac, set <code>ARDUPILOT_LAUNCH_HEADLESS=true</code> (default in <code>.env</code>) so autolaunch does not require <code>gnome-terminal</code>. Use <code>FLIGHT_STACK=ardupilot</code> in <code>.env</code> when the robot stack should use MAVROS APM plugins and <code>is_ardupilot</code> on the interface node.</p>
51375144

51385145

51395146

main/robot/docker/robot-base-docker-compose.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ services:
1717
# MAVROS
1818
- OFFBOARD_BASE_PORT=${OFFBOARD_BASE_PORT}
1919
- ONBOARD_BASE_PORT=${ONBOARD_BASE_PORT}
20+
- FLIGHT_STACK=${FLIGHT_STACK:-px4}
2021
- ROBOT_NAME_MAP_CONFIG_FILE=${ROBOT_NAME_MAP_CONFIG_FILE:-default_robot_name_map.yaml}
2122
volumes:
2223
# display stuff

main/robot/ros_ws/src/interface/interface_bringup/launch/interface.launch.py

Lines changed: 96 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,31 @@
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

1118
import os
1219

1320
from 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+
)
1529
from launch.launch_description_sources import AnyLaunchDescriptionSource
1630
from launch_ros.actions import Node, PushRosNamespace
1731
from 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([
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
<launch>
2+
<arg name="fcu_url" default="/dev/ttyACM0:57600" />
3+
<arg name="gcs_url" default="" />
4+
<arg name="tgt_system" default="1" />
5+
<arg name="tgt_component" default="1" />
6+
<arg name="log_output" default="screen" />
7+
<arg name="fcu_protocol" default="v2.0" />
8+
<arg name="respawn_mavros" default="false" />
9+
<arg name="namespace" default="mavros"/>
10+
11+
<include file="$(find-pkg-share mavros)/launch/node.launch">
12+
<arg name="pluginlists_yaml" value="$(find-pkg-share mavros)/launch/apm_pluginlists.yaml" />
13+
<arg name="config_yaml" value="$(find-pkg-share mavros)/launch/apm_config.yaml" />
14+
<arg name="fcu_url" value="$(var fcu_url)" />
15+
<arg name="gcs_url" value="$(var gcs_url)" />
16+
<arg name="tgt_system" value="$(var tgt_system)" />
17+
<arg name="tgt_component" value="$(var tgt_component)" />
18+
<arg name="log_output" value="$(var log_output)" />
19+
<arg name="fcu_protocol" value="$(var fcu_protocol)" />
20+
<arg name="respawn_mavros" value="$(var respawn_mavros)" />
21+
<arg name="namespace" value="$(var namespace)"/>
22+
</include>
23+
</launch>

main/robot/ros_ws/src/interface/robot_interface/src/odometry_conversion.cpp

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -86,10 +86,17 @@ class OdometryConversion : public rclcpp::Node {
8686
airstack::get_param(this, "odometry_position_translation_post_y", 0.),
8787
airstack::get_param(this, "odometry_position_translation_post_z", 0.));
8888

89+
// QoS must match the odometry publisher. MAVROS local_position/odom (ROS 2 Jazzy)
90+
// uses BEST_EFFORT; a RELIABLE subscriber will not receive those messages.
91+
// Set odom_input_qos_is_best_effort:=false only for publishers that use RELIABLE.
8992
rmw_qos_profile_t qos = rmw_qos_profile_sensor_data;
9093
qos.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
91-
qos.depth = 1;
92-
if (odom_input_qos_is_best_effort) qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
94+
qos.depth = 10;
95+
if (odom_input_qos_is_best_effort) {
96+
qos.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
97+
} else {
98+
qos.reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
99+
}
93100
odom_sub = this->create_subscription<nav_msgs::msg::Odometry>(
94101
"odometry_in", rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(qos), qos),
95102
std::bind(&OdometryConversion::odom_callback, this, std::placeholders::_1));

main/search/search_index.json

Lines changed: 1 addition & 1 deletion
Large diffs are not rendered by default.

main/simulation/isaac-sim/docker/Dockerfile.isaac-ros

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,12 @@
11
# expects context to be the root of the repository, i.e. AirStack/. this is so we can access AirStack/common/
22
ARG ISAAC_VERSION="5.1.0"
33
ARG PX4_VERSION="v1.16.1"
4+
ARG ARDUPILOT_BRANCH="ArduCopter-stable"
45

56
FROM nvcr.io/nvidia/isaac-sim:${ISAAC_VERSION}
67
ARG ISAAC_VERSION
78
ARG PX4_VERSION
9+
ARG ARDUPILOT_BRANCH
810

911
# for install stuff
1012
USER root
@@ -152,6 +154,19 @@ RUN cd PX4-Autopilot && \
152154
RUN cd PX4-Autopilot && \
153155
make px4_sitl
154156

157+
# ArduPilot SITL (Pegasus ArduPilot backend + sim_vehicle); path matches OGN default ardupilotDir
158+
RUN apt-get update && apt-get install -y --no-install-recommends \
159+
gawk python3-wxgtk4.0 python3-pexpect libxml2-dev libxslt1-dev \
160+
&& rm -rf /var/lib/apt/lists/*
161+
162+
RUN git clone --branch ${ARDUPILOT_BRANCH} --depth 1 https://github.com/ArduPilot/ardupilot.git /isaac-sim/ardupilot \
163+
&& cd /isaac-sim/ardupilot \
164+
&& git submodule update --init --recursive \
165+
&& ./waf configure --board sitl \
166+
&& ./waf copter
167+
168+
ENV ARDUPILOT_LAUNCH_HEADLESS=true
169+
155170
RUN /isaac-sim/python.sh -m pip install --no-cache-dir lark-parser
156171

157172
# TMux config

main/simulation/isaac-sim/docker/docker-compose.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ services:
3838
- QT_X11_NO_MITSHM=1
3939
# Isaac Sim stuff
4040
- PLAY_SIM_ON_START=${PLAY_SIM_ON_START}
41+
- ARDUPILOT_LAUNCH_HEADLESS=${ARDUPILOT_LAUNCH_HEADLESS:-true}
42+
- ONBOARD_BASE_PORT=${ONBOARD_BASE_PORT:-14580}
4143
deploy:
4244
# let it use the GPU
4345
resources:

0 commit comments

Comments
 (0)