diff --git a/Tools/ros2/ardupilot_sitl/CMakeLists.txt b/Tools/ros2/ardupilot_sitl/CMakeLists.txt index 4b50d602da..628623f608 100644 --- a/Tools/ros2/ardupilot_sitl/CMakeLists.txt +++ b/Tools/ros2/ardupilot_sitl/CMakeLists.txt @@ -79,6 +79,12 @@ install(DIRECTORY DESTINATION share/${PROJECT_NAME}/config/ ) +# Install additional autotest model params. +install(DIRECTORY + ${ARDUPILOT_ROOT}/Tools/autotest/models + DESTINATION share/${PROJECT_NAME}/config/ +) + # Install Python package. ament_python_install_package(${PROJECT_NAME} PACKAGE_DIR src/${PROJECT_NAME} diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py index a0ea49a58a..12b7009df9 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py @@ -31,6 +31,9 @@ from launch_ros.substitutions import FindPackageShare from .actions import ExecuteFunction +TRUE_STRING = "True" +FALSE_STRING = "False" +BOOL_STRING_CHOICES = set([TRUE_STRING, FALSE_STRING]) class VirtualPortsLaunch: """Launch functions for creating virtual ports using `socat`.""" @@ -307,10 +310,10 @@ class MAVProxyLaunch: "--non-interactive ", ] - if console: + if console == TRUE_STRING: cmd.append("--console ") - if map: + if map == TRUE_STRING: cmd.append("--map ") # Create action. @@ -369,11 +372,13 @@ class MAVProxyLaunch: "map", default_value="False", description="Enable MAVProxy Map.", + choices=BOOL_STRING_CHOICES ), DeclareLaunchArgument( "console", default_value="False", description="Enable MAVProxy Console.", + choices=BOOL_STRING_CHOICES ), ] @@ -419,12 +424,12 @@ class SITLLaunch: # Optional arguments. wipe = LaunchConfiguration("wipe").perform(context) - if wipe == "True": + if wipe == TRUE_STRING: cmd_args.append("--wipe ") print(f"wipe: {wipe}") synthetic_clock = LaunchConfiguration("synthetic_clock").perform(context) - if synthetic_clock == "True": + if synthetic_clock == TRUE_STRING: cmd_args.append("--synthetic-clock ") print(f"synthetic_clock: {synthetic_clock}") @@ -586,13 +591,13 @@ class SITLLaunch: "wipe", default_value="False", description="Wipe eeprom.", - choices=["True", "False"], + choices=BOOL_STRING_CHOICES, ), DeclareLaunchArgument( "synthetic_clock", default_value="False", description="Set synthetic clock mode.", - choices=["True", "False"], + choices=BOOL_STRING_CHOICES, ), DeclareLaunchArgument( "home",