Unable to Take Off in ROS2 SITL – PX4 using customized launch file

Hello everyone,

I am new to ROS2 and PX4. I’ve been working on a ROS2 + PX4 SITL setup and encountered a situation where the pxh> shell is missing when I launch PX4 SITL via a ROS2 launch file. Here’s the launch file I am using:

import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument, ExecuteProcess, SetEnvironmentVariable
from launch.launch_description_sources import PythonLaunchDescriptionSource

def generate_launch_description():
    """Launch Gazebo with PX4 SITL and ROS 2."""
    HOME = os.environ.get('HOME')
    PX4_RUN_DIR = os.path.join(HOME, 'tmp/px4_run_dir')
    PX4_AIRFRAMES_DIR = os.path.join(HOME, 'PX4-Autopilot/build/px4_sitl_default/etc/init.d/airframes')
    gazebo_launch_dir = os.path.join(get_package_share_directory('gazebo_ros'), 'launch')

    # world path
    world_path = os.path.join(HOME, 'PX4-Autopilot/Tools/simulation/gazebo-classic/sitl_gazebo-classic/worlds/empty.world')

    # model path
    setup_package_path = get_package_share_directory('setup')
    model_path = os.path.join(setup_package_path, 'models/px4vision_sls/px4vision_sls.sdf')
    # SetEnvironmentVariable('GAZEBO_MODEL_PATH', os.path.join(setup_package_path, 'models'))

    os.makedirs(PX4_RUN_DIR, exist_ok=True)

    return LaunchDescription([
        # Set environment variables for Gazebo and PX4
        SetEnvironmentVariable('GAZEBO_PLUGIN_PATH', HOME + '/PX4-Autopilot/build/px4_sitl_default/build_gazebo-classic'),
        SetEnvironmentVariable(
            'GAZEBO_MODEL_PATH',
            # Combine PX4 models and custom models
            os.path.join(HOME, 'PX4-Autopilot/Tools/simulation/gazebo-classic/sitl_gazebo-classic/models') + ':' +
            os.path.join(setup_package_path, 'models')
        ),

        # Set Drone ID and Estimator Type
        DeclareLaunchArgument('drone_id', default_value='0', description='PX4 Drone ID'), 
        SetEnvironmentVariable('PX4_SIM_DRONE_ID', LaunchConfiguration('drone_id')),
        SetEnvironmentVariable('PX4_MAV_SYS_ID', LaunchConfiguration('drone_id')),
        DeclareLaunchArgument('est', default_value='ekf2', description='PX4 Estimator Type'),
        SetEnvironmentVariable('PX4_ESTIMATOR', LaunchConfiguration('est')),
        
        # SetEnvironmentVariable('PX4_SYS_AUTOSTART', '10015'),
        # SetEnvironmentVariable('PX4_SYS_AUTOCONFIG', '1'),

        # SetEnvironmentVariable(
        #     'FCU_URL', 'udp://:14540@127.0.0.1:14557'
        # ),

        # Copy airframe files to PX4 run directory (fixes missing model issue)
        ExecuteProcess(
            cmd=['cp', '-r', PX4_AIRFRAMES_DIR, os.path.join(PX4_RUN_DIR, 'etc/init.d-posix/')],
            output='screen'
        ),

        # Declare launch arguments
        DeclareLaunchArgument('world', default_value=world_path),
        DeclareLaunchArgument('model', default_value=model_path),
        DeclareLaunchArgument('x', default_value='0.0'),
        DeclareLaunchArgument('y', default_value='0.0'),
        DeclareLaunchArgument('z', default_value='0.0'),
        DeclareLaunchArgument('R', default_value='0.0'),
        DeclareLaunchArgument('P', default_value='0.0'),
        DeclareLaunchArgument('Y', default_value='0.0'),
        DeclareLaunchArgument('paused', default_value='true'), # start Gazebo in paused mode
        DeclareLaunchArgument('initial_sim_time', default_value=''), # start Gazebo with initial sim time

        # Launch Gazebo server and client
        IncludeLaunchDescription(
            PythonLaunchDescriptionSource([gazebo_launch_dir, '/gzserver.launch.py']),
            launch_arguments={
                'world': LaunchConfiguration('world'),
                'verbose': 'true', 
                'pause': LaunchConfiguration('paused'),
                'initial_sim_time': LaunchConfiguration('initial_sim_time')
            }.items(),
        ),
        IncludeLaunchDescription(
            PythonLaunchDescriptionSource([gazebo_launch_dir, '/gzclient.launch.py'])
        ),

        # Spawn sls
        ExecuteProcess(
            cmd=[
                'gz', 'model',
                '--spawn-file', LaunchConfiguration('model'),
                '--model-name', 'px4vision_sls', 
                '-x', LaunchConfiguration('x'),
                '-y', LaunchConfiguration('y'),
                '-z', LaunchConfiguration('z'),
                '-R', LaunchConfiguration('R'),
                '-P', LaunchConfiguration('P'),
                '-Y', LaunchConfiguration('Y'),
            ],
            prefix="bash -c 'sleep 5s; $0 $@'",
            output='screen'
        ),

        # Start PX4 SITL
        # ExecuteProcess(
        #     cmd=[
        #         HOME + '/PX4-Autopilot/build/px4_sitl_default/bin/px4',
        #         HOME + '/PX4-Autopilot/ROMFS/px4fmu_common/',
        #         '-s', HOME + '/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/rcS',
        #     ],
        #     cwd=PX4_RUN_DIR,
        #     output='screen',
        # ),

        ExecuteProcess(
            cmd=[
                HOME + '/PX4-Autopilot/build/px4_sitl_default/bin/px4',
                HOME + '/PX4-Autopilot/ROMFS/px4fmu_common/',
                '-s', HOME + '/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/rcS',
            ],
            cwd=PX4_RUN_DIR,
            shell=True,
            output='screen'
        ),


        # Start Micro XRCE-DDS Agent for ROS2 <--> PX4 communication
        # start this in another terminal
        # ExecuteProcess(
        #     cmd=['MicroXRCEAgent', 'udp4', '-p', '8888'],
        #     output='screen'),
    ])

And here’s the output message when running the launch file, where “pxh>” doesn’t appear to be available for something like commander command takeoff:

[INFO] [launch]: All log files can be found below /home/yql/.ros/log/2025-03-04-17-58-46-217412-ws3-w-111694
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [cp-1]: process started with pid [111701]
[INFO] [gzserver-2]: process started with pid [111703]
[INFO] [gzclient-3]: process started with pid [111705]
[INFO] [bash-4]: process started with pid [111707]
[INFO] [px4-5]: process started with pid [111710]
[INFO] [cp-1]: process has finished cleanly [pid 111701]
[px4-5]
[px4-5] ______  __   __    ___
[px4-5] | ___ \ \ \ / /   /   |
[px4-5] | |_/ /  \ V /   / /| |
[px4-5] |  __/   /   \  / /_| |
[px4-5] | |     / /^\ \ \___  |
[px4-5] \_|     \/   \/     |_/
[px4-5]
[px4-5] px4 starting.
[px4-5]
[px4-5] INFO  [px4] startup script: /bin/sh /home/yql/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/rcS 0
[px4-5] INFO  [param] selected parameter default file parameters.bson
[px4-5] INFO  [param] importing from 'parameters.bson'
[px4-5] INFO  [parameters] BSON document size 350 bytes, decoded 350 bytes (INT32:15, FLOAT:3)
[px4-5] INFO  [param] selected parameter backup file parameters_backup.bson
[px4-5] INFO  [dataman] data manager file './dataman' size is 7872608 bytes
[px4-5] INFO  [init] PX4_SIM_HOSTNAME: localhost
[px4-5] INFO  [simulator_mavlink] Waiting for simulator to accept connection on TCP port 4560
[gzclient-3] Gazebo multi-robot simulator, version 11.10.2
[gzclient-3] Copyright (C) 2012 Open Source Robotics Foundation.
[gzclient-3] Released under the Apache 2 License.
[gzclient-3] http://gazebosim.org
[gzclient-3]
[gzserver-2] Gazebo multi-robot simulator, version 11.10.2
[gzserver-2] Copyright (C) 2012 Open Source Robotics Foundation.
[gzserver-2] Released under the Apache 2 License.
[gzserver-2] http://gazebosim.org
[gzserver-2]
[gzserver-2] [Wrn] [gazebo_ros_init.cpp:178]
[gzserver-2] #     # ####### ####### ###  #####  #######
[gzserver-2] ##    # #     #    #     #  #     # #
[gzserver-2] # #   # #     #    #     #  #       #
[gzserver-2] #  #  # #     #    #     #  #       #####
[gzserver-2] #   # # #     #    #     #  #       #
[gzserver-2] #    ## #     #    #     #  #     # #
[gzserver-2] #     # #######    #    ###  #####  #######
[gzserver-2]
[gzserver-2] This version of Gazebo, now called Gazebo classic, reaches end-of-life
[gzserver-2] in January 2025. Users are highly encouraged to migrate to the new Gazebo
[gzserver-2] using our migration guides (https://gazebosim.org/docs/latest/gazebo_classic_migration?utm_source=gazebo_ros_pkgs&utm_medium=cli)
[gzserver-2]
[gzserver-2]
[gzclient-3] [Msg] Waiting for master.
[gzclient-3] [Msg] Connected to gazebo master @ http://127.0.0.1:11345
[gzclient-3] [Msg] Publicized address: 10.255.255.254
[gzclient-3] [Wrn] [GuiIface.cc:120] QStandardPaths: wrong permissions on runtime directory /run/user/1000/, 0755 instead of 0700
[gzclient-3] [Wrn] [Event.cc:61] Warning: Deleting a connection right after creation. Make sure to save the ConnectionPtr from a Connect call
[gzclient-3] [Wrn] [Publisher.cc:135] Queue limit reached for topic /gazebo/default/user_camera/pose, deleting message. This warning is printed only once.
[INFO] [bash-4]: process has finished cleanly [pid 111707]
[gzserver-2] [Msg] Waiting for master.
[gzserver-2] [Msg] Connected to gazebo master @ http://127.0.0.1:11345
[gzserver-2] [Msg] Publicized address: 10.255.255.254
[gzserver-2] [Msg] Loading world file [/home/yql/PX4-Autopilot/Tools/simulation/gazebo-classic/sitl_gazebo-classic/worlds/empty.world]
[gzserver-2] [Wrn] [gazebo_gps_plugin.cpp:77] [gazebo_gps_plugin]: px4vision_sls::gps using gps topic "gps"
[gzserver-2] [Wrn] [gazebo_gps_plugin.cpp:202] [gazebo_gps_plugin] Using default update rate of 5hz
[gzserver-2] [Msg] Connecting to PX4 SITL using TCP
[gzserver-2] [Msg] Lockstep is enabled
[gzserver-2] [Msg] Speed factor set to: 1
[gzserver-2] [Wrn] [gazebo_mavlink_interface.cpp:152] No identifier on joint. Using 0 as default sensor ID
[px4-5] INFO  [simulator_mavlink] Simulator connected on TCP port 4560.
[px4-5] INFO  [lockstep_scheduler] setting initial absolute time to 12000 us
[px4-5] INFO  [commander] LED: open /dev/led0 failed (22)
[px4-5] INFO  [uxrce_dds_client] init UDP agent IP:127.0.0.1, port:8888
[px4-5] INFO  [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 18570 remote port 14550
[px4-5] INFO  [mavlink] partner IP: 127.0.0.1
[px4-5] INFO  [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14580 remote port 14540
[px4-5] INFO  [mavlink] mode: Onboard, data rate: 4000 B/s on udp port 14280 remote port 14030
[px4-5] INFO  [mavlink] mode: Gimbal, data rate: 400000 B/s on udp port 13030 remote port 13280
[px4-5] INFO  [logger] logger started (mode=all)
[px4-5] INFO  [logger] Start file log (type: full)
[px4-5] INFO  [logger] [logger] ./log/2025-03-05/00_58_53.ulg
[px4-5] INFO  [logger] Opened full log file: ./log/2025-03-05/00_58_53.ulg
[px4-5] INFO  [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
[px4-5] INFO  [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
[px4-5] INFO  [px4] Startup script returned successfully
[px4-5] pxh> INFO  [tone_alarm] home set
[px4-5] INFO  [uxrce_dds_client] synchronized with time offset 1741136333551138us
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/battery_status data writer, topic id: 19
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/estimator_status_flags data writer, topic id: 83
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 89
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/manual_control_setpoint data writer, topic id: 139
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/position_setpoint_triplet data writer, topic id: 183
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 213
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 236
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_land_detected data writer, topic id: 263
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_attitude data writer, topic id: 250
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_control_mode data writer, topic id: 257
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_global_position data writer, topic id: 258
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_gps_position data writer, topic id: 260
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_local_position data writer, topic id: 264
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_odometry data writer, topic id: 269
[px4-5] INFO  [uxrce_dds_client] successfully created rt/fmu/out/vehicle_status_v1 data writer, topic id: 274
[px4-5] INFO  [uxrce_dds_client] time sync converged
[px4-5] INFO  [commander] Ready for takeoff!


Any guidance, debugging tips, or best practices for combining PX4 SITL and ROS2 in one launch file would be greatly appreciated!

Thank you in advance!