From 3e00ecf84653cc8118eac486a12ab836c4208a36 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Tue, 7 Mar 2023 18:42:53 +0000 Subject: [PATCH] Tools: add ROS 2 launch tests Add ros2.repo for installing packages with vcstool. Add cmake custom targets to run waf configure and build. Update ros2.repo. - Add dependency on arshPratap/ardupilot_ros2.git. - Update version used for ardupilot_ros2.git. - Update ardupilot branch. - Reduce to minimum required. Add ROS 2 launch tests. - Add ROS 2 Python package for testing the AP_DDS library. - Initial version including example Python test. - Move the CMakeLists.txt to ./Tools/scripts/ros2/ardupilot_sitl. - Add virtual port test. Update README. - Add instructions for using the docker image. Disable socat tests return code. - Not portable across platforms? Update ros2.repo - Reduce to minimum required. - Update README. - Update ardupilot_dds_tests packahe.xml Use pytest tmp_path_factory. - Use pytest built-in fixture for tmp directories. Update test README. - Update instructions for running test in docker. Add test config and param files. Add subscriber to Time messages. Clean up virtual port test. - Remove unused code. Test time message is published. - Copied from ardupilot_ros2/pr-ci-test-package branch. Update time msg test - Update workspace relative path. - Remove sleep in main test. Add original time message test. - Add original version of time message test to help resolve failure. Use separate processes for sitl and mavproxy. Update original time message test. Add Python testing to the ardupilot_sitl package. - Add support for Python testing in the ardupilot_sitl package. Add install section to CMakeLists.txt. - Install executables and libs. - Install default params and launch files. Add launch for SITL. - Add example launch file for SITL. - Add local param file in config (test install). Update ROS time message test. Update CMakeLists.txt - Set executable bit when installing programs. Add example launch file for mavproxy. Fix param path in sitl.launch. Fix sitl address and port in example dds test. Rename ardupilot dds yaml config file. Rework sitl.launch to support launch arguments. - Add launch arguments. - Prep work for composing launch files. Rework mavproxy.launch to support launch arguments. - Add launch arguments. - Fix default instance in sitl.launch. - Run as MAVProxy in non-interactive mode. Add launch file for socat virtual port process. - Add separate launch file for process creating virtual ports. Rename launch file for creating virtual ports. - Remove unused import. Add sample config yaml for sitl.launch. Update ros2.repos. - Remove ardupilot_ros2 and micro_ros_setup. - Rename branch. Move ROS 2 packages up a level. Update path to ArduPilot root directory in CMakeLists.txt. Update paths in ros2 dds time message tests Update ros2 README and provide separate ros2.repo for macOS. - Add build instructions for each platform. - Provide separate ros2.repos for macOS which has additional dependencies to build from source. Add composite launch for sitl and mavproxy. -Provide example of composite launch that reuses existing launch files. Add uart and serial port arguments to sitl.launch - Add extra (optional) arguments for ports. - Handle default arguments (e.g. wipe and synthetic clock). - Remove use of TextSubstitution which seems redundant. Simplify and update formatting in mavproxy and virtual port launches. - Update print formatting. - Remove use of TextSubstitution. Add launch file for micro_ros_agent. - The launch file in the micro_ros_agent does not have launch arguments. - Replace hardcoded transport. Correct install path for launch files in setup.py. - Correct install path for launch files. - Format line length. Update micro_ros_agent launch. - Do not use None for launch argument default value. Add composite launch file for the time message test. - Compose launch from four simpler launch files. Comment unused variables for linting. Install dds profile. - Update CMakeLists.txt to install the dds_xrceprofile. - Move install location of dds.parm to config/default_params. - Update README with notes on equivalent command line calls. Correct launch for micro_ros_agent. - Remove extra space prefixing device field. - Update README with example launch commands. Update launch examples in README - Update README with example launch commands. Update combined launch for DDS time message test. - Add events to combined launch to control launch sequence. - Update README with example command for combined launch. Remove dds.parm from ardupilot_dds_tests. - File moved to ardupilot_sitl. Update combined launch for DDS time message test. - Disable events as these will not work with a launch description as the target_action. Rename launch file for bringing up sitl with dds. Rename virtual ports launch test. Use PathJoinSubstitution and FindPackageShare for package resolution. - Use substitutions for package and launch path resolution. Update launch example in readme. - Fix typo in combined launch. Update virtual ports test case. Rename virtual ports test case. Rename time message test case. Rework the time msg test case to use previously defined launch files. Add time message check node. Clean up test cases. Move bringup fixture into conftest.py. - Factor out bringup fixture. Remove unused code and imports. Add test for navsatfix. - Update qos profile for navsatfix test. Update test case names. Use pathlib instead of os.path. Set speedup to 10, reduce test timeout. Update CMakeLists.txt - Remove --debug. - Remove commented code. Update sitl_launch.py. - Use max_serial_ports instead of hardcoded number. Remove sample python test. Update maintainer for ros2 packages. Update ros2.repos. - Point to ardupilot master instead of fork and PR branch. Update CMakeLists.txt. - Fix format (indent) in build test section. Enable ament linters and use black formatter. - Enable ament_lint_auto in CMakeLists.txt. - Override default flake8 config to prevent conflicts with black formatter. - Update README. - Update files to satisfy linters. More PEP 257 compliance. - Adopt recommended style for comments. Apply linters and formatter. - Apply linter and black formatter to ardupilot_dds_tests. - Move package tests under folder. - Reinstate copyright, flake8 and pep257 tests. Reorganise ros2 launch files - Move launch files for SITL from ardupilot_dds_tests to ardupilit_sitl. - Update docs. Signed-off-by: Rhys Mainwaring --- Tools/ros2/README.md | 249 ++++++++++++++++++ Tools/ros2/ardupilot_dds_tests/.flake8 | 10 + .../ardupilot_dds_tests/__init__.py | 16 ++ .../ardupilot_dds_tests/time_listener.py | 69 +++++ .../config/ardupilot_dds.yaml | 13 + .../ros2/ardupilot_dds_tests/launch/README.md | 1 + Tools/ros2/ardupilot_dds_tests/package.xml | 31 +++ .../resource/ardupilot_dds_tests | 0 Tools/ros2/ardupilot_dds_tests/setup.cfg | 4 + Tools/ros2/ardupilot_dds_tests/setup.py | 34 +++ .../test/ardupilot_dds_tests/conftest.py | 160 +++++++++++ .../ardupilot_dds_tests/param_loader_wip.py | 58 ++++ .../test_navsat_msg_received.py | 98 +++++++ .../test_time_msg_received.py | 90 +++++++ .../ardupilot_dds_tests/test_virtual_ports.py | 136 ++++++++++ .../test/test_copyright.py | 25 ++ .../ardupilot_dds_tests/test/test_flake8.py | 27 ++ .../ardupilot_dds_tests/test/test_pep257.py | 25 ++ Tools/ros2/ardupilot_sitl/.flake8 | 10 + Tools/ros2/ardupilot_sitl/CMakeLists.txt | 112 ++++++++ .../ardupilot_sitl/ardupilot_sitl/__init__.py | 16 ++ .../ardupilot_sitl/config/copter_quad.yaml | 23 ++ .../config/default_params/dds.parm | 2 + .../ardupilot_sitl/launch/mavproxy.launch.py | 97 +++++++ .../launch/micro_ros_agent.launch.py | 128 +++++++++ .../ros2/ardupilot_sitl/launch/sitl.launch.py | 213 +++++++++++++++ .../ardupilot_sitl/launch/sitl_dds.launch.py | 94 +++++++ .../launch/sitl_mavproxy.launch.py | 60 +++++ .../launch/virtual_ports.launch.py | 78 ++++++ Tools/ros2/ardupilot_sitl/package.xml | 21 ++ Tools/ros2/ros2.repos | 9 + Tools/ros2/ros2_macos.repos | 17 ++ 32 files changed, 1926 insertions(+) create mode 100644 Tools/ros2/README.md create mode 100644 Tools/ros2/ardupilot_dds_tests/.flake8 create mode 100644 Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/__init__.py create mode 100755 Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py create mode 100644 Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml create mode 100644 Tools/ros2/ardupilot_dds_tests/launch/README.md create mode 100644 Tools/ros2/ardupilot_dds_tests/package.xml create mode 100644 Tools/ros2/ardupilot_dds_tests/resource/ardupilot_dds_tests create mode 100644 Tools/ros2/ardupilot_dds_tests/setup.cfg create mode 100644 Tools/ros2/ardupilot_dds_tests/setup.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/test_copyright.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/test_flake8.py create mode 100644 Tools/ros2/ardupilot_dds_tests/test/test_pep257.py create mode 100644 Tools/ros2/ardupilot_sitl/.flake8 create mode 100644 Tools/ros2/ardupilot_sitl/CMakeLists.txt create mode 100644 Tools/ros2/ardupilot_sitl/ardupilot_sitl/__init__.py create mode 100644 Tools/ros2/ardupilot_sitl/config/copter_quad.yaml create mode 100644 Tools/ros2/ardupilot_sitl/config/default_params/dds.parm create mode 100644 Tools/ros2/ardupilot_sitl/launch/mavproxy.launch.py create mode 100644 Tools/ros2/ardupilot_sitl/launch/micro_ros_agent.launch.py create mode 100644 Tools/ros2/ardupilot_sitl/launch/sitl.launch.py create mode 100644 Tools/ros2/ardupilot_sitl/launch/sitl_dds.launch.py create mode 100644 Tools/ros2/ardupilot_sitl/launch/sitl_mavproxy.launch.py create mode 100644 Tools/ros2/ardupilot_sitl/launch/virtual_ports.launch.py create mode 100644 Tools/ros2/ardupilot_sitl/package.xml create mode 100644 Tools/ros2/ros2.repos create mode 100644 Tools/ros2/ros2_macos.repos diff --git a/Tools/ros2/README.md b/Tools/ros2/README.md new file mode 100644 index 0000000000000..8cd8a63c5ed4f --- /dev/null +++ b/Tools/ros2/README.md @@ -0,0 +1,249 @@ +# 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: + +#### `ardupilot_sitl` + +A `colcon` package for building and running ArduPilot SITL using the ROS 2 CLI. +For example `ardurover` SITL may be launched with: + +```bash +ros2 launch ardupilot_sitl sitl.launch.py command:=ardurover model:=rover +``` + +#### `ardupilot_dds_test` + +A `colcon` package for testing communication between `micro_ros_agent` and the +ArduPilot `AP_DDS` client library. + +## Prerequisites + +The packages depend on: + +- [ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html) + + +## Install Ubuntu + +#### 1. Create a workspace folder + +```bash +mkdir -p ~/ros_ws/src && cd ~/ros_ws/src +``` + +The ROS 2 tutorials contain more details regarding [ROS 2 workspaces](https://docs.ros.org/en/humble/Tutorials/Workspace/Creating-A-Workspace.html). + +#### 2. Get the `ros2.repos` file + +```bash +cd ~/ros2_ws/src +wget https://raw.githubusercontent.com/srmainwaring/ardupilot/pr/pr-dds-launch-tests/Tools/ros2/ros2.repos +vcs import --recursive < ros2.repos +``` + +#### 3. Update dependencies + +```bash +cd ~/ros_ws +source /opt/ros/humble/setup.bash +sudo apt update +rosdep update +rosdep install --rosdistro humble --from-paths src +``` + +#### 4. Build + +```bash +cd ~/ros_ws +colcon build --packages-select micro_ros_agent +colcon build --packages-select ardupilot_sitl +colcon build --packages-select ardupilot_dds_tests +``` + +#### 5. Test + +```bash +source ./install/setup.bash +colcon test --pytest-args -s -v --event-handlers console_cohesion+ --packages-select ardupilot_dds_tests +colcon test-result --all --verbose +``` + +## Install macOS + +The install procedure on macOS is similar, except that all dependencies +must be built from source and additional compiler flags are needed. + +#### 1. Create a workspace folder + +```bash +mkdir -p ~/ros_ws/src && cd ~/ros_ws/src +``` + +#### 2. Get the `ros2.repos` file + +The `ros2_macos.repos` includes additional dependencies to build: + +```bash +cd ~/ros2_ws/src +wget https://raw.githubusercontent.com/srmainwaring/ardupilot/pr/pr-dds-launch-tests/Tools/ros2/ros2_macos.repos +vcs import --recursive < ros2_macos.repos +``` + +#### 3. Update dependencies + +```bash +cd ~/ros_ws +source //install/setup.zsh +``` + +#### 4.1. Build microxrcedds_gen: + +```bash +cd ~/ros2_ws/src/microxrcedds_gen +./gradlew assemble +export PATH=$PATH:$(pwd)/scripts +``` + +#### 4.2. Build colcon projects + +```bash +colcon build --symlink-install --cmake-args \ +-DBUILD_TESTING=ON \ +-DCMAKE_BUILD_TYPE=RelWithDebInfo \ +-DCMAKE_MACOSX_RPATH=FALSE \ +-DUAGENT_SOCKETCAN_PROFILE=OFF \ +-DUAGENT_LOGGER_PROFILE=OFF \ +-DUAGENT_USE_SYSTEM_LOGGER=OFF \ +-DUAGENT_USE_SYSTEM_FASTDDS=ON \ +-DUAGENT_USE_SYSTEM_FASTCDR=ON \ +--event-handlers=desktop_notification- \ +--packages-select \ +micro_ros_msgs \ +micro_ros_agent \ +ardupilot_sitl \ +ardupilot_dds_tests +``` + +#### 5. Test + +```bash +colcon test \ +--pytest-args -s -v \ +--event-handlers console_cohesion+ desktop_notification- \ +--packages-select ardupilot_dds_tests +``` + +## Install Docker + +#### 0. Build the image and run the container + +Clone the ArduPilot docker project: + +```bash +git clone https://github.com/ArduPilot/ardupilot_dev_docker.git +``` + +Build the container: + +```bash +cd ~/ardupilot_dev_docker/docker +docker build -t ardupilot/ardupilot-dev-ros -f Dockerfile_dev-ros . +``` + +Start the container in interactive mode: + +```bash +docker run -it --name ardupilot-dds ardupilot/ardupilot-dev-ros +``` + +Connect another bash process to the running container: + +```bash +docker container exec -it ardupilot-dds /bin/bash +``` + +The remaining steps 1 - 5 are the same as for Ubuntu. You may need to +install MAVProxy if it is not available on the container. + + +```bash +pip install -U MAVProxy +``` + + +## Test details + +The launch file replicates the following commands: + +```bash +socat -d -d pty,raw,echo=0,link=./dev/ttyROS0 pty,raw,echo=0,link=./dev/ttyROS1 +``` + +```bash +ros2 run micro_ros_agent micro_ros_agent serial --baudrate 115200 --dev ./dev/ttyROS0 --refs $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml +``` + +```bash +arducopter --synthetic-clock --wipe --model quad --speedup 1 --slave 0 --instance 0 --uartC uart:./dev/ttyROS1 --defaults $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds.parm --sim-address 127.0.0.1 +``` + +```bash +mavproxy.py --out 127.0.0.1:14550 --out 127.0.0.1:14551 --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 +``` + +Using individual launch files + +```bash +ros2 launch ardupilot_sitl virtual_ports.launch.py tty0:=./dev/ttyROS0 tty1:=./dev/ttyROS1 +``` + +```bash +ros2 launch ardupilot_sitl micro_ros_agent.launch.py refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml baudrate:=115200 device:=./dev/ttyROS0 +``` + +```bash +ros2 launch ardupilot_sitl sitl.launch.py synthetic_clock:=True wipe:=True model:=quad speedup:=1 slave:=0 instance:=0 uartC:=uart:./dev/ttyROS1 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds.parm sim_address:=127.0.0.1 +``` + +```bash +ros2 launch ardupilot_sitl mavproxy.launch.py master:=tcp:127.0.0.1:5760 sitl:=127.0.0.1:5501 +``` + +Using combined launch file + +```bash +ros2 launch ardupilot_sitl sitl_dds.launch.py \ +\ +tty0:=./dev/ttyROS0 \ +tty1:=./dev/ttyROS1 \ +\ +refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml \ +baudrate:=115200 \ +device:=./dev/ttyROS0 \ +\ +synthetic_clock:=True \ +wipe:=True \ +model:=quad \ +speedup:=1 \ +slave:=0 \ +instance:=0 \ +uartC:=uart:./dev/ttyROS1 \ +defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds.parm \ +sim_address:=127.0.0.1 \ +\ +master:=tcp:127.0.0.1:5760 \ +sitl:=127.0.0.1:5501 +``` + +## References + +### Configuring linters and formatters for ROS 2 projects + +- [ROS 2 Code style and language versions](https://docs.ros.org/en/humble/The-ROS2-Project/Contributing/Code-Style-Language-Versions.html). +- [Configuring Flake8](https://flake8.pycqa.org/en/latest/user/configuration.html). +- [ament_lint_auto](https://github.com/ament/ament_lint/blob/humble/ament_lint_auto/doc/index.rst). +- [How to configure ament python linters in CMakeLists?](https://answers.ros.org/question/351012/how-to-configure-ament-python-linters-in-cmakelists/). +- [Using black and flake8 in tandem](https://sbarnea.com/lint/black/). + diff --git a/Tools/ros2/ardupilot_dds_tests/.flake8 b/Tools/ros2/ardupilot_dds_tests/.flake8 new file mode 100644 index 0000000000000..b79f25fa41199 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/.flake8 @@ -0,0 +1,10 @@ +[flake8] +# Match black line length (default 88). +max-line-length = 88 +# Match black configuration where there are conflicts. +extend-ignore = + # Q000: Double quotes found but single quotes preferred + Q000, + # W503: Line break before binary operator + W503 + diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/__init__.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/__init__.py new file mode 100644 index 0000000000000..c50c1d44fe983 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/__init__.py @@ -0,0 +1,16 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Main entry point for the `ardupilot_dds_tests` package.""" diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py new file mode 100755 index 0000000000000..8ac693a9586dd --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py @@ -0,0 +1,69 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Subscribe to Time messages on topic /ROS2_Time.""" +import rclpy +import time + +from rclpy.node import Node +from builtin_interfaces.msg import Time + + +class TimeListener(Node): + """Subscribe to Time messages on topic /ROS2_Time.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("time_listener") + + # Declare and acquire `topic` parameter. + self.declare_parameter("topic", "ROS2_Time") + self.topic = self.get_parameter("topic").get_parameter_value().string_value + + # Subscriptions. + self.subscription = self.create_subscription(Time, self.topic, self.cb, 1) + self.subscription + + def cb(self, msg): + """Process a Time message.""" + if msg.sec: + self.get_logger().info( + "From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec) + ) + else: + self.get_logger().info("From AP : False") + + +def main(args=None): + """Node entry point.""" + rclpy.init(args=args) + node = TimeListener() + try: + count = 0 + while count < 100: + rclpy.spin_once(node) + count += 1 + time.sleep(1.0) + + except KeyboardInterrupt: + pass + + # Destroy the node explicitly. + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml b/Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml new file mode 100644 index 0000000000000..67d472c34fb94 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/config/ardupilot_dds.yaml @@ -0,0 +1,13 @@ +/micro_ros_agent: + transport: serial + middleware: dds + serial_baud: 115200 + serial_device: ./dev/ttyROS0 + refs_file: ./src/ardupilot/libraries/AP_DDS/dds_xrce_profile.xml + +/ardupilot: + sim_vehicle_cmd: ./src/ardupilot/Tools/autotest/sim_vehicle.py + vehicle: ArduCopter + frame: quad + serial_baud: 115200 + serial_device: ./dev/ttyROS1 diff --git a/Tools/ros2/ardupilot_dds_tests/launch/README.md b/Tools/ros2/ardupilot_dds_tests/launch/README.md new file mode 100644 index 0000000000000..3a868074aa1e7 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/launch/README.md @@ -0,0 +1 @@ +## Placeholder for `ardupilot_dds_tests` launch files. diff --git a/Tools/ros2/ardupilot_dds_tests/package.xml b/Tools/ros2/ardupilot_dds_tests/package.xml new file mode 100644 index 0000000000000..64e6670881260 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/package.xml @@ -0,0 +1,31 @@ + + + + ardupilot_dds_tests + 0.0.0 + Tests for the ArduPilot AP_DDS library + rhys + GLP-3.0 + + ament_index_python + launch + launch_pytest + launch_ros + micro_ros_msgs + python3-pytest + rclpy + + ament_copyright + ament_flake8 + ament_pep257 + launch + launch_pytest + launch_ros + micro_ros_msgs + python3-pytest + rclpy + + + ament_python + + diff --git a/Tools/ros2/ardupilot_dds_tests/resource/ardupilot_dds_tests b/Tools/ros2/ardupilot_dds_tests/resource/ardupilot_dds_tests new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/Tools/ros2/ardupilot_dds_tests/setup.cfg b/Tools/ros2/ardupilot_dds_tests/setup.cfg new file mode 100644 index 0000000000000..ef1e9abe74841 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/ardupilot_dds_tests +[install] +install_scripts=$base/lib/ardupilot_dds_tests diff --git a/Tools/ros2/ardupilot_dds_tests/setup.py b/Tools/ros2/ardupilot_dds_tests/setup.py new file mode 100644 index 0000000000000..ce6e894687c5c --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/setup.py @@ -0,0 +1,34 @@ +import os +from glob import glob +from setuptools import setup + +package_name = 'ardupilot_dds_tests' + +setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (os.path.join("share", package_name, "launch"), + glob("launch/*.launch.py")), + (os.path.join("share", package_name, "config"), + glob("config/*.parm")), + (os.path.join("share", package_name, "config"), + glob("config/*.yaml")), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='maintainer', + maintainer_email='maintainer@ardupilot.org', + description='Tests for the ArduPilot AP_DDS library', + license='GPL-3.0', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + "time_listener = ardupilot_dds_tests.time_listener:main", + ], + }, +) diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py new file mode 100644 index 0000000000000..7fa92b7e6c7da --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py @@ -0,0 +1,160 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Common fixtures.""" +import os +import pytest + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import PathJoinSubstitution + +from launch_ros.substitutions import FindPackageShare + +from pathlib import Path + + +@pytest.fixture(scope="module") +def device_dir(tmp_path_factory): + """Fixture to create a temporary directory for devices.""" + path = tmp_path_factory.mktemp("devices") + return path + + +@pytest.fixture +def sitl_dds(device_dir): + """Fixture to bring up ArduPilot SITL DDS.""" + # Create directory for virtual ports. + print(f"\ntmpdirname: {device_dir}\n") + if not ("dev" in os.listdir(device_dir)): + os.mkdir(Path(device_dir, "dev")) + + # Full path to virtual ports. + tty0 = Path(device_dir, "dev", "tty0").resolve() + tty1 = Path(device_dir, "dev", "tty1").resolve() + + virtual_ports = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "virtual_ports.launch.py", + ] + ), + ] + ), + launch_arguments={ + "tty0": str(tty0), + "tty1": str(tty1), + }.items(), + ) + + micro_ros_agent = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "micro_ros_agent.launch.py", + ] + ), + ] + ), + launch_arguments={ + "refs": PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "config", + "dds_xrce_profile.xml", + ] + ), + "baudrate": "115200", + "device": str(tty0), + }.items(), + ) + + sitl = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "sitl.launch.py", + ] + ), + ] + ), + launch_arguments={ + "command": "arducopter", + "synthetic_clock": "True", + "wipe": "True", + "model": "quad", + "speedup": "10", + "slave": "0", + "instance": "0", + "uartC": f"uart:{str(tty1)}", + "defaults": str( + Path( + get_package_share_directory("ardupilot_sitl"), + "config", + "default_params", + "copter.parm", + ) + ) + + "," + + str( + Path( + get_package_share_directory("ardupilot_sitl"), + "config", + "default_params", + "dds.parm", + ) + ), + }.items(), + ) + + mavproxy = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "mavproxy.launch.py", + ] + ), + ] + ), + launch_arguments={ + "master": "tcp:127.0.0.1:5760", + "sitl": "127.0.0.1:5501", + }.items(), + ) + + return LaunchDescription( + [ + virtual_ports, + micro_ros_agent, + sitl, + mavproxy, + ] + ) diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py new file mode 100644 index 0000000000000..f8c8a5efb881d --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/param_loader_wip.py @@ -0,0 +1,58 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Loader parameters for test cases (WIP).""" + +# from pathlib import Path +# +# class DDSParams(object): +# def __init__(self): +# super().__init__() +# +# # default params +# self.mra_serial_device = f"./dev/ttyROS0" +# self.mra_serial_baud = 115200 +# self.mra_refs_file = "dds_xrce_profile.xml" +# +# self.ap_sim_vehicle_cmd = "sim_vehicle.py" +# self.ap_serial_device = f"./dev/ttyROS1" +# self.ap_serial_baud = 115200 +# self.ap_vehicle = "ArduCopter" +# self.ap_frame = "quad" +# +# pkg = get_package_share_directory("ardupilot_sitl") +# +# # The micro_ros_agent and ardupilot nodes do not expose params +# # as ROS params, parse the config file and send them in as node args. +# params = Path(pkg, "config", "ardupilot_dds.yaml") +# +# with open(params, "r") as f: +# params_str = f.read() +# params = yaml.safe_load(params_str) +# print(params) +# +# mra_params = params["/micro_ros_agent"] +# if mra_params["transport"] == "serial": +# self.mra_serial_baud = f"{mra_params['serial_baud']}" +# self.mra_serial_device = f"{mra_params['serial_device']}" +# self.mra_refs_file = f"{mra_params['refs_file']}" +# +# ap_params = params["/ardupilot"] +# if ap_params: +# self.ap_sim_vehicle_cmd = ap_params["sim_vehicle_cmd"] +# self.ap_vehicle = ap_params["vehicle"] +# self.ap_frame = ap_params["frame"] +# self.ap_serial_device = ap_params["serial_device"] +# self.ap_serial_baud = ap_params["serial_baud"] diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py new file mode 100644 index 0000000000000..c1c0326967ff9 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py @@ -0,0 +1,98 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Bring up ArduPilot SITL and check the NavSat message is being published.""" +import launch_pytest +import pytest +import rclpy +import rclpy.node +import threading + +from launch import LaunchDescription + +from rclpy.qos import QoSProfile, QoSReliabilityPolicy, QoSHistoryPolicy + +from sensor_msgs.msg import NavSatFix + + +@launch_pytest.fixture +def launch_description(sitl_dds): + """Fixture to create the launch description.""" + return LaunchDescription( + [ + sitl_dds, + launch_pytest.actions.ReadyToTest(), + ] + ) + + +class NavSatFixListener(rclpy.node.Node): + """Subscribe to NavSatFix messages on /ROS2_NavSatFix0.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("navsatfix_listener") + self.msg_event_object = threading.Event() + + # Declare and acquire `topic` parameter + self.declare_parameter("topic", "ROS2_NavSatFix0") + self.topic = self.get_parameter("topic").get_parameter_value().string_value + + def start_subscriber(self): + """Start the subscriber.""" + qos_profile = QoSProfile( + reliability=QoSReliabilityPolicy.BEST_EFFORT, + history=QoSHistoryPolicy.KEEP_LAST, + depth=1, + ) + + self.subscription = self.create_subscription( + NavSatFix, self.topic, self.subscriber_callback, qos_profile + ) + + # Add a spin thread. + self.ros_spin_thread = threading.Thread( + target=lambda node: rclpy.spin(node), args=(self,) + ) + self.ros_spin_thread.start() + + def subscriber_callback(self, msg): + """Process a NavSatFix message.""" + self.msg_event_object.set() + + if msg.latitude: + self.get_logger().info( + "From AP : True [lat:{}, lon: {}]".format(msg.latitude, msg.longitude) + ) + else: + self.get_logger().info("From AP : False") + + +@pytest.mark.launch(fixture=launch_description) +def test_navsat_msgs_received(sitl_dds, launch_context): + """Test NavSatFix messages are published by AP_DDS.""" + rclpy.init() + try: + node = NavSatFixListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, "Did not receive 'ROS2_NavSatFix0' msgs." + finally: + rclpy.shutdown() + + yield + + # Anything below this line is executed after launch service shutdown. + pass diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py new file mode 100644 index 0000000000000..851b7805ed9d4 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py @@ -0,0 +1,90 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Bring up ArduPilot SITL check the Time message is being published.""" +import launch_pytest +import pytest +import rclpy +import rclpy.node +import threading + +from launch import LaunchDescription + +from builtin_interfaces.msg import Time + + +@launch_pytest.fixture +def launch_description(sitl_dds): + """Fixture to create the launch description.""" + return LaunchDescription( + [ + sitl_dds, + launch_pytest.actions.ReadyToTest(), + ] + ) + + +class TimeListener(rclpy.node.Node): + """Subscribe to Time messages on /ROS2_Time.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("time_listener") + self.msg_event_object = threading.Event() + + # Declare and acquire `topic` parameter. + self.declare_parameter("topic", "ROS2_Time") + self.topic = self.get_parameter("topic").get_parameter_value().string_value + + def start_subscriber(self): + """Start the subscriber.""" + self.subscription = self.create_subscription( + Time, self.topic, self.subscriber_callback, 1 + ) + + # Add a spin thread. + self.ros_spin_thread = threading.Thread( + target=lambda node: rclpy.spin(node), args=(self,) + ) + self.ros_spin_thread.start() + + def subscriber_callback(self, msg): + """Process a Time message.""" + self.msg_event_object.set() + + if msg.sec: + self.get_logger().info( + "From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec) + ) + else: + self.get_logger().info("From AP : False") + + +@pytest.mark.launch(fixture=launch_description) +def test_time_msgs_received(sitl_dds, launch_context): + """Test Time messages are published by AP_DDS.""" + rclpy.init() + try: + node = TimeListener() + node.start_subscriber() + msgs_received_flag = node.msg_event_object.wait(timeout=10.0) + assert msgs_received_flag, "Did not receive 'ROS_Time' msgs." + finally: + rclpy.shutdown() + + yield + + # Anything below this line is executed after launch service shutdown. + pass diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py new file mode 100644 index 0000000000000..a355c8e95f589 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py @@ -0,0 +1,136 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Use `socat` to create virtual ports ttyROS0 and ttyRO1 and check they exist.""" +import os +import launch_pytest +import pytest + +from launch import LaunchDescription +from launch.actions import EmitEvent +from launch.actions import ExecuteProcess +from launch.actions import IncludeLaunchDescription +from launch.actions import LogInfo +from launch.actions import RegisterEventHandler +from launch.event_handlers import OnProcessStart +from launch.event_handlers import OnProcessExit +from launch.events import matches_action +from launch.events.process import ShutdownProcess +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import PathJoinSubstitution + +from launch_pytest.tools import process as process_tools + +from launch_ros.substitutions import FindPackageShare + +from pathlib import Path + + +@pytest.fixture() +def dummy_proc(): + """Return a dummy process action to manage test lifetime.""" + return ExecuteProcess( + cmd=["echo", "ardupilot_dds_tests"], + shell=True, + cached_output=True, + ) + + +@pytest.fixture() +def virtual_ports(device_dir): + """Fixture that includes and configures the virtual port launch.""" + # Create directory for virtual ports. + print(f"\ntmpdirname: {device_dir}\n") + if not ("dev" in os.listdir(device_dir)): + os.mkdir(Path(device_dir, "dev")) + + # Full path to virtual ports. + tty0 = Path(device_dir, "dev", "tty0").resolve() + tty1 = Path(device_dir, "dev", "tty1").resolve() + + virtual_ports = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "virtual_ports.launch.py", + ] + ), + ] + ), + launch_arguments={ + "tty0": str(tty0), + "tty1": str(tty1), + }.items(), + ) + return virtual_ports + + +@launch_pytest.fixture() +def launch_description(dummy_proc, virtual_ports): + """Fixture to create the launch description.""" + on_start = RegisterEventHandler( + event_handler=OnProcessStart( + target_action=dummy_proc, + on_start=[ + LogInfo(msg="Test started."), + ], + ) + ) + + on_process_exit = RegisterEventHandler( + event_handler=OnProcessExit( + target_action=dummy_proc, + on_exit=[ + LogInfo(msg="Test stopping."), + EmitEvent( + event=ShutdownProcess(process_matcher=matches_action(virtual_ports)) + ), + ], + ) + ) + + return LaunchDescription( + [ + dummy_proc, + virtual_ports, + on_start, + on_process_exit, + launch_pytest.actions.ReadyToTest(), + ] + ) + + +@pytest.mark.launch(fixture=launch_description) +def test_virtual_ports(dummy_proc, virtual_ports, launch_context): + """Test the virtual ports are present.""" + # TODO: check virtial port process for regex: + # "starting data transfer loop" + + def validate_output(output): + assert output.splitlines() == [ + "ardupilot_dds_tests" + ], "Test process had no output." + + process_tools.assert_output_sync( + launch_context, dummy_proc, validate_output, timeout=5 + ) + + yield + + # Anything below this line is executed after launch service shutdown. + assert dummy_proc.return_code == 0 diff --git a/Tools/ros2/ardupilot_dds_tests/test/test_copyright.py b/Tools/ros2/ardupilot_dds_tests/test/test_copyright.py new file mode 100644 index 0000000000000..0ba906088ba2c --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/test_copyright.py @@ -0,0 +1,25 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Test files include a copyright notice.""" +from ament_copyright.main import main +import pytest + + +@pytest.mark.copyright +@pytest.mark.linter +def test_copyright(): + """Copyright test case.""" + rc = main(argv=[".", "test"]) + assert rc == 0, "Found errors" diff --git a/Tools/ros2/ardupilot_dds_tests/test/test_flake8.py b/Tools/ros2/ardupilot_dds_tests/test/test_flake8.py new file mode 100644 index 0000000000000..17771247a5472 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/test_flake8.py @@ -0,0 +1,27 @@ +# Copyright 2017 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Test Python files satisfy the flake8 linter requirements.""" +from ament_flake8.main import main_with_errors +import pytest + + +@pytest.mark.flake8 +@pytest.mark.linter +def test_flake8(): + """flake8 test case.""" + rc, errors = main_with_errors(argv=[]) + assert rc == 0, "Found %d code style errors / warnings:\n" % len( + errors + ) + "\n".join(errors) diff --git a/Tools/ros2/ardupilot_dds_tests/test/test_pep257.py b/Tools/ros2/ardupilot_dds_tests/test/test_pep257.py new file mode 100644 index 0000000000000..c46d13e9730fd --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/test/test_pep257.py @@ -0,0 +1,25 @@ +# Copyright 2015 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Test Python files satisfy PEP257.""" +from ament_pep257.main import main +import pytest + + +@pytest.mark.linter +@pytest.mark.pep257 +def test_pep257(): + """PEP257 test case.""" + rc = main(argv=[".", "test"]) + assert rc == 0, "Found code style errors / warnings" diff --git a/Tools/ros2/ardupilot_sitl/.flake8 b/Tools/ros2/ardupilot_sitl/.flake8 new file mode 100644 index 0000000000000..b79f25fa41199 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/.flake8 @@ -0,0 +1,10 @@ +[flake8] +# Match black line length (default 88). +max-line-length = 88 +# Match black configuration where there are conflicts. +extend-ignore = + # Q000: Double quotes found but single quotes preferred + Q000, + # W503: Line break before binary operator + W503 + diff --git a/Tools/ros2/ardupilot_sitl/CMakeLists.txt b/Tools/ros2/ardupilot_sitl/CMakeLists.txt new file mode 100644 index 0000000000000..433b1cc48d292 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/CMakeLists.txt @@ -0,0 +1,112 @@ +cmake_minimum_required(VERSION 3.20) +project(ardupilot_sitl) + +# --------------------------------------------------------------------------- # +# Find dependencies. +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) + +# --------------------------------------------------------------------------- # +# Add custom targets to configure and build ardupilot. + +# TODO(srmainwaring): add cache variables for vehicle type, debug etc. +# set(ARDUPILOT_VEHICLE "copter" CACHE STRING "Vehicle type") + +# NOTE: look for `waf` and set source and build directories to top level. +# ${PROJECT_SOURCE_DIR} = ./Tools/ros2/ardupilot +# +cmake_path(SET ARDUPILOT_ROOT NORMALIZE ${PROJECT_SOURCE_DIR}/../../..) + +find_program(WAF_COMMAND waf HINTS ${ARDUPILOT_ROOT}) +message(STATUS "WAF_COMMAND: ${WAF_COMMAND}") + +add_custom_target(ardupilot_configure ALL + ${WAF_COMMAND} configure --board sitl --enable-dds + WORKING_DIRECTORY ${ARDUPILOT_ROOT} +) + +add_custom_target(ardupilot_build ALL + ${WAF_COMMAND} build --enable-dds + WORKING_DIRECTORY ${ARDUPILOT_ROOT} +) +add_dependencies(ardupilot_build ardupilot_configure) + +# --------------------------------------------------------------------------- # +# Install. + +# Install executables. +install(PROGRAMS + ${ARDUPILOT_ROOT}/build/sitl/bin/antennatracker + ${ARDUPILOT_ROOT}/build/sitl/bin/arducopter + ${ARDUPILOT_ROOT}/build/sitl/bin/arducopter-heli + ${ARDUPILOT_ROOT}/build/sitl/bin/arduplane + ${ARDUPILOT_ROOT}/build/sitl/bin/ardurover + ${ARDUPILOT_ROOT}/build/sitl/bin/ardusub + ${ARDUPILOT_ROOT}/build/sitl/bin/blimp + DESTINATION bin/ +) + +# Install libs. +install(DIRECTORY + ${ARDUPILOT_ROOT}/build/sitl/lib + DESTINATION ./ +) + +# Install launch files. +install(DIRECTORY + launch + DESTINATION share/${PROJECT_NAME}/ +) + +# Install DDS profile. +install(FILES + ${ARDUPILOT_ROOT}/libraries/AP_DDS/dds_xrce_profile.xml + DESTINATION share/${PROJECT_NAME}/config +) + +# Install additional default params. +install(DIRECTORY + config/default_params + DESTINATION share/${PROJECT_NAME}/config +) + +# Install autotest default params. +install(DIRECTORY + ${ARDUPILOT_ROOT}/Tools/autotest/default_params + DESTINATION share/${PROJECT_NAME}/config/ +) + +# Install Python package. +ament_python_install_package(${PROJECT_NAME}) + +# --------------------------------------------------------------------------- # +# build tests + +if(BUILD_TESTING) + # Override default flake8 configuration. + set(ament_cmake_flake8_CONFIG_FILE ${CMAKE_SOURCE_DIR}/.flake8) + + # Add linters. + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + # Add python tests. + find_package(ament_cmake_pytest REQUIRED) + set(_pytest_tests + # Add tests here, for example: + # tests/test_a.py + ) + foreach(_test_path ${_pytest_tests}) + get_filename_component(_test_name ${_test_path} NAME_WE) + ament_add_pytest_test(${_test_name} ${_test_path} + APPEND_ENV PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR} + TIMEOUT 60 + WORKING_DIRECTORY ${CMAKE_SOURCE_DIR} + ) + endforeach() +endif() + +# --------------------------------------------------------------------------- # +# Call last. + +ament_package() diff --git a/Tools/ros2/ardupilot_sitl/ardupilot_sitl/__init__.py b/Tools/ros2/ardupilot_sitl/ardupilot_sitl/__init__.py new file mode 100644 index 0000000000000..9691b39d98099 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/ardupilot_sitl/__init__.py @@ -0,0 +1,16 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +"""Main entry point for the `ardupilot_sitl` package.""" diff --git a/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml b/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml new file mode 100644 index 0000000000000..02ad121f3a9c9 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml @@ -0,0 +1,23 @@ +/sitl: + wipe: true + speedup: 1 + instance: 0 + synthetic_clock: true + model: quad + slave: 0 + sim_address: 127.0.0.1 + defaults: copter.parm + + # unused + # rate: 400 + # console: true + # home: [lat, lon, alt, yaw] + # uartA: /dev/tty0 + # uartB: /dev/tty1 + # serial0: /dev/usb0 + # serial1: /dev/usb1 + # sim_port_in: 5501 + # sim_port_out: 5501 + # irlock_port: 5501 + # sysid: 255 + diff --git a/Tools/ros2/ardupilot_sitl/config/default_params/dds.parm b/Tools/ros2/ardupilot_sitl/config/default_params/dds.parm new file mode 100644 index 0000000000000..80767ed1d74e5 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/config/default_params/dds.parm @@ -0,0 +1,2 @@ +SERIAL1_BAUD 115 +SERIAL1_PROTOCOL 45 diff --git a/Tools/ros2/ardupilot_sitl/launch/mavproxy.launch.py b/Tools/ros2/ardupilot_sitl/launch/mavproxy.launch.py new file mode 100644 index 0000000000000..4faa222abf75c --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/launch/mavproxy.launch.py @@ -0,0 +1,97 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Launch a non-interactive instance of MAVProxy. + +Run with default arguments: + +ros2 launch ardupilot_sitl mavproxy.launch.py + +Show launch arguments: + +ros2 launch ardupilot_sitl mavproxy.launch.py --show-args +""" +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import ExecuteProcess +from launch.actions import OpaqueFunction +from launch.substitutions import LaunchConfiguration + + +def launch_mavproxy(context, *args, **kwargs): + """Return a non-interactive MAVProxy process.""" + # Declare the command. + command = "mavproxy.py" + + # Retrieve launch arguments. + master = LaunchConfiguration("master").perform(context) + # out = LaunchConfiguration("out").perform(context) + sitl = LaunchConfiguration("sitl").perform(context) + + # Display launch arguments. + print(f"command: {command}") + print(f"master: {master}") + print(f"sitl: {sitl}") + + # Create action. + mavproxy_process = ExecuteProcess( + cmd=[ + [ + f"{command} ", + "--out ", + "127.0.0.1:14550 ", + "--out ", + "127.0.0.1:14551 ", + f"--master {master} ", + f"--sitl {sitl} ", + "--non-interactive ", + # "--daemon " + ] + ], + shell=True, + output="both", + respawn=False, + ) + + launch_processes = [mavproxy_process] + return launch_processes + + +def generate_launch_description(): + """Generate a launch description for MAVProxy.""" + # Create launch description. + return LaunchDescription( + [ + # Launch arguments. + DeclareLaunchArgument( + "master", + default_value="tcp:127.0.0.1:5760", + description="MAVLink master port and optional baud rate.", + ), + DeclareLaunchArgument( + "out", + default_value="127.0.0.1:14550", + description="MAVLink output port and optional baud rate.", + ), + DeclareLaunchArgument( + "sitl", + default_value="127.0.0.1:5501", + description="SITL output port.", + ), + # Launch function. + OpaqueFunction(function=launch_mavproxy), + ] + ) diff --git a/Tools/ros2/ardupilot_sitl/launch/micro_ros_agent.launch.py b/Tools/ros2/ardupilot_sitl/launch/micro_ros_agent.launch.py new file mode 100644 index 0000000000000..e8013f60765f5 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/launch/micro_ros_agent.launch.py @@ -0,0 +1,128 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Launch the microROS DDS agent. + +Run with default arguments: + +ros2 launch ardupilot_sitl micro_ros_agent.launch.py +""" +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import OpaqueFunction +from launch.substitutions import LaunchConfiguration + +import launch_ros + + +def launch_micro_ros_agent(context, *args, **kwargs): + """Launch the micro_ros_agent node.""" + # ROS arguments. + micro_ros_agent_ns = LaunchConfiguration("micro_ros_agent_ns").perform(context) + + # Common arguments. + transport = LaunchConfiguration("transport").perform(context) + middleware = LaunchConfiguration("middleware").perform(context) + refs = LaunchConfiguration("refs").perform(context) + verbose = LaunchConfiguration("verbose").perform(context) + # discovery = LaunchConfiguration("discovery").perform(context) + + # Serial arguments. + device = LaunchConfiguration("device").perform(context) + baudrate = LaunchConfiguration("baudrate").perform(context) + + # Display launch arguments. + print(f"namespace: {micro_ros_agent_ns}") + print(f"transport: {transport}") + print(f"middleware: {middleware}") + print(f"refs: {refs}") + print(f"verbose: {verbose}") + # print(f"discovery: {discovery}") + + print(f"baudrate: {baudrate}") + print(f"device: {device}") + + # Create action. + micro_ros_agent_node = launch_ros.actions.Node( + package="micro_ros_agent", + namespace=f"{micro_ros_agent_ns}", + executable="micro_ros_agent", + name="micro_ros_agent", + output="both", + arguments=[ + {transport}, + "--middleware", + {middleware}, + "--refs", + {refs}, + "--dev", + {device}, + "--baudrate", + {baudrate}, + ], + # additional_env={"PYTHONUNBUFFERED": "1"}, + ) + + launch_processes = [micro_ros_agent_node] + return launch_processes + + +def generate_launch_description(): + """Generate a launch description for the micro_ros_agent.""" + return LaunchDescription( + [ + # Launch arguments. + DeclareLaunchArgument( + "micro_ros_agent_ns", + default_value="", + description="Set the micro_ros_agent namespace.", + ), + DeclareLaunchArgument( + "transport", + default_value="serial", + description="Set the transport.", + choices=["serial"], + ), + DeclareLaunchArgument( + "middleware", + default_value="dds", + description="Set the middleware.", + choices=["ced", "dds", "rtps"], + ), + DeclareLaunchArgument( + "refs", + default_value="", + description="Set the refs file.", + ), + DeclareLaunchArgument( + "verbose", + default_value="", + description="Set the verbosity level.", + ), + DeclareLaunchArgument( + "baudrate", + default_value="", + description="Set the baudrate.", + ), + DeclareLaunchArgument( + "device", + default_value="", + description="Set the device.", + ), + # Launch function. + OpaqueFunction(function=launch_micro_ros_agent), + ] + ) diff --git a/Tools/ros2/ardupilot_sitl/launch/sitl.launch.py b/Tools/ros2/ardupilot_sitl/launch/sitl.launch.py new file mode 100644 index 0000000000000..ca5aba8172582 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/launch/sitl.launch.py @@ -0,0 +1,213 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Launch ArduPilot SITL. + +Run with default arguments: + +ros2 launch ardupilot_sitl sitl.launch.py + +Show launch arguments: + +ros2 launch ardupilot_sitl sitl.launch.py --show-args +""" + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import ExecuteProcess +from launch.actions import OpaqueFunction +from launch.substitutions import LaunchConfiguration +from launch.substitutions import PathJoinSubstitution + +from launch_ros.substitutions import FindPackageShare + +# Labels for the optional uart launch arguments. +uart_labels = ["A", "B", "C", "D", "E", "F", "H", "I", "J"] +max_serial_ports = 10 + + +def launch_sitl(context, *args, **kwargs): + """Return a SITL process.""" + command = LaunchConfiguration("command").perform(context) + model = LaunchConfiguration("model").perform(context) + speedup = LaunchConfiguration("speedup").perform(context) + slave = LaunchConfiguration("slave").perform(context) + sim_address = LaunchConfiguration("sim_address").perform(context) + instance = LaunchConfiguration("instance").perform(context) + defaults = LaunchConfiguration("defaults").perform(context) + + # Display launch arguments. + print(f"command: {command}") + print(f"model: {model}") + print(f"speedup: {speedup}") + print(f"slave: {slave}") + print(f"sim_address: {sim_address}") + print(f"instance: {instance}") + print(f"defaults: {defaults}") + + # Required arguments. + cmd_args = [ + f"{command} ", + f"--model {model} ", + f"--speedup {speedup} ", + f"--slave {slave} ", + f"--sim-address={sim_address} ", + f"--instance {instance} ", + f"--defaults {defaults} ", + ] + + # Optional arguments. + wipe = LaunchConfiguration("wipe").perform(context) + if wipe == "True": + cmd_args.append("--wipe ") + print(f"wipe: {wipe}") + + synthetic_clock = LaunchConfiguration("synthetic_clock").perform(context) + if synthetic_clock == "True": + cmd_args.append("--synthetic-clock ") + print(f"synthetic_clock: {synthetic_clock}") + + home = LaunchConfiguration("home").perform(context) + if home: + cmd_args.append("--home {home} ") + print(f"home: {home}") + + # Optional uart arguments. + for label in uart_labels: + arg = LaunchConfiguration(f"uart{label}").perform(context) + if arg: + cmd_args.append(f"--uart{label} {arg} ") + print(f"uart{label}: {arg}") + + # Optional serial arguments. + for label in range(10): + arg = LaunchConfiguration(f"serial{label}").perform(context) + if arg: + cmd_args.append(f"--serial{label} {arg} ") + print(f"serial{label}: {arg}") + + # Create action. + sitl_process = ExecuteProcess( + cmd=[cmd_args], + shell=True, + output="both", + respawn=False, + ) + + launch_processes = [sitl_process] + return launch_processes + + +def generate_launch_description(): + """Generate a launch description for SITL.""" + # UART launch arguments. + uart_args = [] + for label in uart_labels: + arg = DeclareLaunchArgument( + f"uart{label}", + default_value="", + description=f"set device string for UART{label}.", + ) + uart_args.append(arg) + + # Serial launch arguments. + serial_args = [] + for label in range(max_serial_ports): + arg = DeclareLaunchArgument( + f"serial{label}", + default_value="", + description=f"set device string for SERIAL{label}.", + ) + serial_args.append(arg) + + return LaunchDescription( + [ + # Launch arguments. + DeclareLaunchArgument( + "command", + default_value="arducopter", + description="Run ArduPilot SITL.", + choices=[ + "antennatracker", + "arducopter-heli", + "ardurover", + "blimp", + "arducopter", + "arduplane", + "ardusub", + ], + ), + DeclareLaunchArgument( + "model", + default_value="quad", + description="Set simulation model.", + ), + DeclareLaunchArgument( + "slave", + default_value="0", + description="Set the number of JSON slaves.", + ), + DeclareLaunchArgument( + "sim_address", + default_value="127.0.0.1", + description="Set address string for simulator.", + ), + DeclareLaunchArgument( + "speedup", + default_value="1", + description="Set simulation speedup.", + ), + DeclareLaunchArgument( + "instance", + default_value="0", + description="Set instance of SITL " + "(adds 10*instance to all port numbers).", + ), + DeclareLaunchArgument( + "defaults", + default_value=PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "config", + "default_params", + "copter.parm", + ] + ), + description="Set path to defaults file.", + ), + # Optional launch arguments. + DeclareLaunchArgument( + "wipe", + default_value="False", + description="Wipe eeprom.", + choices=["True", "False"], + ), + DeclareLaunchArgument( + "synthetic_clock", + default_value="False", + description="Set synthetic clock mode.", + choices=["True", "False"], + ), + DeclareLaunchArgument( + "home", + default_value="", + description="Set start location (lat,lng,alt,yaw) " "or location name.", + ), + ] + + uart_args + + serial_args + + [OpaqueFunction(function=launch_sitl)] + ) diff --git a/Tools/ros2/ardupilot_sitl/launch/sitl_dds.launch.py b/Tools/ros2/ardupilot_sitl/launch/sitl_dds.launch.py new file mode 100644 index 0000000000000..ec229603c45d5 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/launch/sitl_dds.launch.py @@ -0,0 +1,94 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Launch ArduPilot SITL, MAVProxy and the microROS DDS agent. + +Run with default arguments: + +ros2 launch ardupilot_sitl sitl_dds.launch.py +""" +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import PathJoinSubstitution + +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + """Generate a launch description to bring up ArduPilot SITL with DDS.""" + # Include component launch files. + virtual_ports = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "virtual_ports.launch.py", + ] + ), + ] + ) + ) + micro_ros_agent = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "micro_ros_agent.launch.py", + ] + ), + ] + ) + ) + sitl = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "sitl.launch.py", + ] + ), + ] + ) + ) + mavproxy = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "mavproxy.launch.py", + ] + ), + ] + ) + ) + + return LaunchDescription( + [ + virtual_ports, + micro_ros_agent, + sitl, + mavproxy, + ] + ) diff --git a/Tools/ros2/ardupilot_sitl/launch/sitl_mavproxy.launch.py b/Tools/ros2/ardupilot_sitl/launch/sitl_mavproxy.launch.py new file mode 100644 index 0000000000000..95107e6e0b3d6 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/launch/sitl_mavproxy.launch.py @@ -0,0 +1,60 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Launch ArduPilot SITL and a non-interactive instance of MAVProxy. + +Run with default arguments: + +ros2 launch ardupilot_sitl sitl_mavproxy.launch.py +""" +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import PathJoinSubstitution + +from launch_ros.substitutions import FindPackageShare + + +def generate_launch_description(): + """Generate a launch description for combined SITL and MAVProxy.""" + sitl = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "sitl.launch.py", + ] + ), + ] + ) + ) + mavproxy = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + [ + PathJoinSubstitution( + [ + FindPackageShare("ardupilot_sitl"), + "launch", + "mavproxy.launch.py", + ] + ), + ] + ) + ) + + return LaunchDescription([sitl, mavproxy]) diff --git a/Tools/ros2/ardupilot_sitl/launch/virtual_ports.launch.py b/Tools/ros2/ardupilot_sitl/launch/virtual_ports.launch.py new file mode 100644 index 0000000000000..a0872ab8aaa79 --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/launch/virtual_ports.launch.py @@ -0,0 +1,78 @@ +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Launch a process to create virtual ports. + +Run with default arguments: + +ros2 launch ardupilot_sitl virtual_ports.launch.py +""" +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument +from launch.actions import ExecuteProcess +from launch.actions import OpaqueFunction +from launch.substitutions import LaunchConfiguration + + +def launch_socat(context, *args, **kwargs): + """Launch a process to create virtual ports using `socat`.""" + command = "socat" + tty0 = LaunchConfiguration("tty0").perform(context) + tty1 = LaunchConfiguration("tty1").perform(context) + + # Display launch arguments. + print(f"command: {command}") + print(f"tty0: {tty0}") + print(f"tty1: {tty1}") + + # Create action. + socat_process = ExecuteProcess( + cmd=[ + [ + "socat ", + "-d -d ", + f"pty,raw,echo=0,link={tty0} ", + f"pty,raw,echo=0,link={tty1} ", + ] + ], + shell=True, + output="both", + respawn=False, + ) + + launch_processes = [socat_process] + return launch_processes + + +def generate_launch_description(): + """Generate a launch description for creating virtual ports using `socat`.""" + return LaunchDescription( + [ + # Launch arguments. + DeclareLaunchArgument( + "tty0", + default_value="tty0", + description="Symbolic link name for tty0.", + ), + DeclareLaunchArgument( + "tty1", + default_value="tty1", + description="Symbolic link name for tty1.", + ), + # Launch function. + OpaqueFunction(function=launch_socat), + ] + ) diff --git a/Tools/ros2/ardupilot_sitl/package.xml b/Tools/ros2/ardupilot_sitl/package.xml new file mode 100644 index 0000000000000..21ae2dfa2975e --- /dev/null +++ b/Tools/ros2/ardupilot_sitl/package.xml @@ -0,0 +1,21 @@ + + + + ardupilot_sitl + 0.0.0 + ArduPlane, ArduCopter, ArduRover, ArduSub source + maintainer + GPL-3.0 + + ament_cmake + ament_cmake_python + + ament_cmake_pytest + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/Tools/ros2/ros2.repos b/Tools/ros2/ros2.repos new file mode 100644 index 0000000000000..77c0b5c97ccec --- /dev/null +++ b/Tools/ros2/ros2.repos @@ -0,0 +1,9 @@ +repositories: + ardupilot: + type: git + url: https://github.com/ArduPilot/ardupilot.git + version: master + micro_ros_agent: + type: git + url: https://github.com/micro-ROS/micro-ROS-Agent.git + version: humble diff --git a/Tools/ros2/ros2_macos.repos b/Tools/ros2/ros2_macos.repos new file mode 100644 index 0000000000000..84bca3e85089c --- /dev/null +++ b/Tools/ros2/ros2_macos.repos @@ -0,0 +1,17 @@ +repositories: + ardupilot: + type: git + url: https://github.com/srmainwaring/ardupilot.git + version: pr/pr-dds-launch-tests + microxrcedds_gen: + type: git + url: https://github.com/eProsima/Micro-XRCE-DDS-Gen.git + version: develop + micro_ros_agent: + type: git + url: https://github.com/srmainwaring/micro-ROS-Agent.git + version: cmake-macos + micro_ros_msgs: + type: git + url: https://github.com/micro-ROS/micro_ros_msgs.git + version: humble