ardupilot/Tools/ros2/README.md

247 lines
6.6 KiB
Markdown
Raw Normal View History

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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
# 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/ArduPilot/ardupilot/master/Tools/ros2/ros2.repos
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
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 ${ROS_DISTRO} --from-paths src
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```
#### 4. Build
Check that the [ROS environment](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html#check-environment-variables) is configured correctly:
```bash
ROS_VERSION=2
ROS_PYTHON_VERSION=3
ROS_DISTRO=humble
```
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```bash
cd ~/ros_ws
colcon build --cmake-args -DBUILD_TESTING=ON
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```
#### 5. Test
```bash
source ./install/setup.bash
colcon test --packages-select ardupilot_dds_tests
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
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_macos.repos` file
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
The `ros2_macos.repos` includes additional dependencies to build:
```bash
cd ~/ros2_ws/src
wget https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/ros2_macos.repos
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
vcs import --recursive < ros2_macos.repos
```
#### 3. Update dependencies
```bash
cd ~/ros_ws
source /{path_to_your_ros_distro_workspace}/install/setup.zsh
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```
#### 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-
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```
#### 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_serial.parm --sim-address 127.0.0.1
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```
```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 transport:=serial refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml baudrate:=115200 device:=./dev/ttyROS0
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```
```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_serial.parm sim_address:=127.0.0.1
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
```
```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_serial.launch.py \
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
\
tty0:=./dev/ttyROS0 \
tty1:=./dev/ttyROS1 \
\
transport:=serial \
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
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_serial.parm \
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 <rhys.mainwaring@me.com>
2023-03-07 14:42:53 -04:00
sim_address:=127.0.0.1 \
\
master:=tcp:127.0.0.1:5760 \
sitl:=127.0.0.1:5501
```
UDP version
```
ros2 launch ardupilot_sitl sitl_dds_udp.launch.py transport:=udp4 refs:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/dds_xrce_profile.xml synthetic_clock:=True wipe:=False model:=quad speedup:=1 slave:=0 instance:=0 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_udp.parm sim_address:=127.0.0.1 master:=tcp:127.0.0.1:5760 sitl:=127.0.0.1:5501
```