Skip to content

Commit

Permalink
ROS Jazzy support
Browse files Browse the repository at this point in the history
  • Loading branch information
pedro-fuoco committed Nov 7, 2024
1 parent 57865ea commit 0bcfaad
Show file tree
Hide file tree
Showing 3 changed files with 70 additions and 34 deletions.
24 changes: 18 additions & 6 deletions dev/source/docs/ros2-gazebo.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,16 +17,28 @@ Ensure you have the prerequisites complete and working before beginning this Gaz
Install Gazebo
==============

First, install `Gazebo Harmonic (recommended) <https://gazebosim.org/docs/harmonic/install>`__ or `Gazebo Garden <https://gazebosim.org/docs/garden/install>`__.
First, install `Gazebo Harmonic (recommended) <https://gazebosim.org/docs/harmonic/install>`__ or `Gazebo Garden <https://gazebosim.org/docs/garden/install>`__. Please check the `Compatibility Matrix between ROS and Gazebo versions <https://gazebosim.org/docs/latest/ros_installation/#summary-of-compatible-ros-and-gazebo-combinations>`__.

Next, set up all the necessary ROS 2 packages in the workspace.

We will clone the required repositories using `vcstool <https://github.com/dirk-thomas/vcstool>`__ and a `ros2.repos` files:
We will clone the required repositories using `vcstool <https://github.com/dirk-thomas/vcstool>`__ and a `.repos` files:

.. code-block:: bash
.. tabs::

.. tab:: Jazzy

.. code-block:: bash
cd ~/ardu_ws
vcs import --input https://raw.githubusercontent.com/ArduPilot/ardupilot_gz/main/jazzy_gz.repos --recursive src
.. tab:: Humble

.. code-block:: bash
cd ~/ardu_ws
vcs import --input https://raw.githubusercontent.com/ArduPilot/ardupilot_gz/main/humble_gz.repos --recursive src
cd ~/ardu_ws
vcs import --input https://raw.githubusercontent.com/ArduPilot/ardupilot_gz/main/ros2_gz.repos --recursive src
Set the Gazebo version to either ``harmonic`` (recommended) or ``garden``.
It's recommended to set this in your `~/.bashrc` file.
Expand All @@ -40,7 +52,7 @@ Update ROS dependencies:
.. code-block:: bash
cd ~/ardu_ws
source /opt/ros/humble/setup.bash
source /opt/ros/$ROS_DISTRO/setup.bash
sudo apt update
rosdep update
rosdep install --from-paths src --ignore-src -r
Expand Down
15 changes: 8 additions & 7 deletions dev/source/docs/ros2-sitl.rst
Original file line number Diff line number Diff line change
Expand Up @@ -10,26 +10,27 @@ You will need to run this command on every new shell you open to have access to

.. tabs::

.. group-tab:: ArduPilot 4.5
.. group-tab:: ArduPilot 4.6 and later

.. code-block:: bash
source /opt/ros/humble/setup.bash
source /opt/ros/$ROS_DISTRO/setup.bash
cd ~/ardu_ws/
colcon build --packages-up-to ardupilot_sitl
source install/setup.bash
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
ros2 launch ardupilot_sitl sitl_dds_udp.launch.py transport:=udp4 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
.. group-tab:: ArduPilot 4.6 and later
.. group-tab:: ArduPilot 4.5

.. code-block:: bash
source /opt/ros/humble/setup.bash
source /opt/ros/$ROS_DISTRO/setup.bash
cd ~/ardu_ws/
colcon build --packages-up-to ardupilot_sitl
source install/setup.bash
ros2 launch ardupilot_sitl sitl_dds_udp.launch.py transport:=udp4 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
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
Expand Down
65 changes: 44 additions & 21 deletions dev/source/docs/ros2.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,49 +17,59 @@ Prerequisites

- Learn to use ArduPilot first by following the relevant wiki for `Rover <https://ardupilot.org/rover/index.html>`__, `Copter <https://ardupilot.org/copter/index.html>`__ or `Plane <https://ardupilot.org/plane/index.html>`__.
- In particular, make sure the vehicle works well in Manual and Autonomous modes like Guided and Auto before trying to use ROS.
- Learn how to use ROS 2 by reading the `beginner tutorials <https://docs.ros.org/en/humble/Tutorials.html>`__. In the case of a problem with ROS, it is best to ask on ROS community forums first (or google your error).
- Learn how to use ROS 2 by reading the `beginner tutorials <https://docs.ros.org/en/rolling/Tutorials.html>`__. In the case of a problem with ROS, it is best to ask on ROS community forums first (or google your error).

We are keen to improve ArduPilot's support of ROS 2 so if you find issues (such as commands that do not seem to be supported), please report them in the `ArduPilot issues list <https://github.com/ArduPilot/ardupilot/issues>`__. A maintainer can add the `ROS` tag.

First, make sure that you have successfully installed `ROS 2 Humble <https://docs.ros.org/en/humble/Installation.html>`__ .
Currently, ROS 2 Humble is the only version supported.
First, make sure that you have successfully installed and configured your ROS 2 environment. ArduPilot supports ROS 2 `Humble <https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html>`__ and `Jazzy <https://docs.ros.org/en/jazzy/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html>`__.

You are about to create a new `ROS 2 workspace <https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace.html#id4>`__.
This page assumes that your workspace is named `ardu_ws` in your home directory, but feel free to adjust to your preferred location.

Before anything else, make sure that you have `sourced your ROS 2 environment <https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html#source-the-setup-files>`__
and check if it is `configured correctly <https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.html#check-environment-variables>`__.

Finally, ensure you have `set up your ArduPilot build environment <https://ardupilot.org/dev/docs/building-the-code.html#setting-up-the-build-environment>`__.
This document suggests creating a new ROS 2 workspace from scratch, named `ardu_ws`, located in your home folder. If you already have a working ROS 2 workspace, feel free to adapt the instructions to your needs.

Installation (Ubuntu)
=====================

To make installation easy, we will clone the required repositories using `vcs` and a `ros2.repos` files:
To make installation easy, we will clone the required repositories using `vcs` and a `.repos` files:

.. code-block:: bash
.. tabs::

mkdir -p ~/ardu_ws/src
cd ~/ardu_ws
vcs import --recursive --input https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/ros2.repos src
.. tab:: Jazzy

.. code-block:: bash
mkdir -p ~/ardu_ws/src
cd ~/ardu_ws
vcs import --recursive --input https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/jazzy.repos src
.. tab:: Humble

.. code-block:: bash
mkdir -p ~/ardu_ws/src
cd ~/ardu_ws
vcs import --recursive --input https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/humble.repos src
This will take a few minutes to clone all the repositories your first time.

Now update all dependencies:
.. warning::
The `ardupilot` repository will be cloned in the `~/ardu_ws/src` folder during this process. Before proceeding, `set up your ArduPilot build environment <https://ardupilot.org/dev/docs/building-the-code.html#setting-up-the-build-environment>`__ inside the ROS 2 workspace.
If you already have a working ArduPilot build environment, you may move it inside the workspace instead, but be sure to change all script references too. It might be a good idea to check your `.bashrc`.

Now update all dependencies using `rosdep`:

.. code-block:: bash
cd ~/ardu_ws
sudo apt update
rosdep update
source /opt/ros/humble/setup.bash
rosdep install --from-paths src --ignore-src -r -y
Installing the `MicroXRCEDDSGen` build dependency:

.. code-block:: bash
sudo apt install default-jre
# Gradle 7.6 is not supported by java versions >= 20
# https://docs.gradle.org/current/userguide/compatibility.html
sudo apt install openjdk-17-jre
cd ~/ardu_ws
git clone --recurse-submodules https://github.com/ardupilot/Micro-XRCE-DDS-Gen.git
cd Micro-XRCE-DDS-Gen
Expand Down Expand Up @@ -133,10 +143,23 @@ Installation (MacOS)

To make installation easy, we will install the required packages using `vcs` and a `ros2_macos.repos` files:

.. code-block:: bash
.. tabs::

cd ~/ardu_ws
vcs import --recursive --input https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/ros2_macos.repos src
.. tab:: Jazzy

.. code-block:: bash
mkdir -p ~/ardu_ws/src
cd ~/ardu_ws
vcs import --recursive --input https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/jazzy_macos.repos src
.. tab:: Humble

.. code-block:: bash
mkdir -p ~/ardu_ws/src
cd ~/ardu_ws
vcs import --recursive --input https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/humble_macos.repos src
Now update all dependencies:

Expand Down

0 comments on commit 0bcfaad

Please sign in to comment.