diff --git a/Tools/ros2/README.md b/Tools/ros2/README.md index c6d6504517..d847eeea3a 100644 --- a/Tools/ros2/README.md +++ b/Tools/ros2/README.md @@ -1,12 +1,12 @@ # ArduPilot ROS 2 packages - This directory contains ROS 2 packages and configuration files for running - ROS 2 processes and nodes that communicate with the ArduPilot DDS client - library using the microROS agent. It contains the following packages: +This directory contains ROS 2 packages and configuration files for running +ROS 2 processes and nodes that communicate with the ArduPilot DDS client +library using the microROS agent. It contains the following packages: #### `ardupilot_sitl` -A `colcon` package for building and running ArduPilot SITL using the ROS 2 CLI. +This is a `colcon` package for building and running ArduPilot SITL using the ROS 2 CLI. For example `ardurover` SITL may be launched with: ```bash @@ -21,6 +21,14 @@ For example, MAVProxy can be launched, and you can enable the `console` and `map ros2 launch ardupilot_sitl sitl_mavproxy.launch.py map:=True console:=True ``` +ArduPilot SITL does not yet expose all arguments from the underlying binary. +See [#27714](https://github.com/ArduPilot/ardupilot/issues/27714) for context. + +To see all current options, use the `-s` argument: +```bash +ros2 launch ardupilot_sitl sitl.launch.py -s +``` + #### `ardupilot_dds_test` A `colcon` package for testing communication between `micro_ros_agent` and the diff --git a/Tools/ros2/ardupilot_dds_tests/package.xml b/Tools/ros2/ardupilot_dds_tests/package.xml index b4cc9fa2a0..528f4794a1 100644 --- a/Tools/ros2/ardupilot_dds_tests/package.xml +++ b/Tools/ros2/ardupilot_dds_tests/package.xml @@ -27,12 +27,15 @@ ament_lint_auto ardupilot_msgs ardupilot_sitl + builtin_interfaces launch launch_pytest launch_ros micro_ros_msgs python3-pytest rclpy + sensor_msgs + ament_python diff --git a/Tools/ros2/ardupilot_sitl/package.xml b/Tools/ros2/ardupilot_sitl/package.xml index 5cc0abfd72..fd1cc359ed 100644 --- a/Tools/ros2/ardupilot_sitl/package.xml +++ b/Tools/ros2/ardupilot_sitl/package.xml @@ -11,7 +11,15 @@ ament_cmake ament_cmake_python + ardupilot_msgs + builtin_interfaces + geographic_msgs + geometry_msgs micro_ros_agent + rosgraph_msgs + sensor_msgs + std_msgs + tf2_msgs ament_lint_auto ament_cmake_black