Skip to content

Commit

Permalink
Dev: Add ROS 2 ethernet support information
Browse files Browse the repository at this point in the history
Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Mar 24, 2024
1 parent cf7cc27 commit 22ef1a3
Show file tree
Hide file tree
Showing 2 changed files with 98 additions and 0 deletions.
1 change: 1 addition & 0 deletions dev/source/docs/ros.rst
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ These pages will show you how to:
ROS 2 with SITL <ros2-sitl>
ROS with SITL in Gazebo <ros-gazebo>
ROS 2 with SITL in Gazebo <ros2-gazebo>
ROS 2 over Ethernet <ros2-over-ethernet>
Cartographer SLAM with ROS 2 in SITL <ros2-cartographer-slam>
ROS with distance sensors <ros-distance-sensors>
ROS with Aruco Boards detection <ros-aruco-detection>
Expand Down
97 changes: 97 additions & 0 deletions dev/source/docs/ros2-over-ethernet.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
.. _ros2-over-ethernet:

===================
ROS 2 over Ethernet
===================

The following tutorial explains how to connect a flight controller to a companion computer using ethernet for DDS communication.

Ensure you have ROS 2 :ref:`installed <ros2>` and have run :ref:`SITL <ros2-sitl>` successfully before attempting this page.

Additionally, make sure you understand the :ref:`basics of networking in ArduPilot. <common-network>`

==========
Motivation
==========

Starting in ArduPilot 4.5, ethernet is now supported as a new communication interface.
Compared to connecting an autopilot over serial, ethernet has the following advantages:

* Ethernet is more immune to noise because it uses twisted pair wiring
* Ethernet can run multiple protocols over the same protocol (unless you use PPP)
* Ethernet is easier to debug with tools such as ``tcpdump`` or ``Wireshark``
* Ethernet uses standard cabling, so it's more difficult to mix up TX and RX

==================
Physical Equipment
==================

The following equipment is required to complete this tutorial:

* A computer that can run the MicroROS Agent and the ROS 2 CLI
* An autopilot with ethernet support

=============================================
Necessary parameters for static configuration
=============================================

This list of parameters is given as an example.
If you had the following static IP addresses:

* An autopilot has the IP address ``192.168.1.6``
* A Computer running the MicroROS agent has the IP address ``192.168.1.5``
* The MicroROS agent is running on port ``2019``

Then, you would configure all of the below parameters.


.. list-table::
:widths: 50 50
:header-rows: 1

* - Parameter Name
- Value
* - :ref:`DDS_ENABLE<DDS_ENABLE>`
- 1
* - :ref:`DDS_IP0<DDS_IP0>`
- 192
* - :ref:`DDS_IP1<DDS_IP1>`
- 168
* - :ref:`DDS_IP2<DDS_IP2>`
- 1
* - :ref:`DDS_IP3<DDS_IP3>`
- 6
* - :ref:`DDS_UDP_PORT<DDS_UDP_PORT>`
- 2019
* - :ref:`NET_DHCP<NET_DHCP>`
- 0
* - :ref:`NET_ENABLED<NET_ENABLED>`
- 1
* - :ref:`NET_IPADDR0<NET_IPADDR0>`
- 192
* - :ref:`NET_IPADDR1<NET_IPADDR1>`
- 168
* - :ref:`NET_IPADDR2<NET_IPADDR2>`
- 1
* - :ref:`NET_IPADDR3<NET_IPADDR3>`
- 5


Modify the addresses to suit your needs; the rest can remain the same.

=====
Steps
=====

#. Flash the autopilot with software compiled with ``--enable-dds``
#. Connect the autopilot via ethernet to the computer
#. Open a MavProxy session
#. Configure the parameters described above, starting with the ``ENABLE`` parameters first.
#. Reboot the flight controller
#. Start the MicroROS Agent with the same port as the parameter for ``DDS_UDP_PORT``

.. code-block:: bash
ros2 run micro_ros_agent micro_ros_agent udp4 -p 2019 -r dds_xrce_profile.xml
#. Use the ROS 2 CLI to interact with the autopilot

0 comments on commit 22ef1a3

Please sign in to comment.