Customizing your DDS Configuration
Like most ROS 2 applications, MoveIt Pro relies on a DDS based ROS middleware (RMW) for intercommunication between processes. In MoveIt Pro, we support Eclipse Cyclone DDS and eprosima Fast RTPS (formally FastDDS) middlewares.
By default, MoveIt Pro uses a Cyclone DDS configuration that:
- Will communicate with ROS 2 processes inside the MoveIt Pro docker container.
- Will communicate with ROS 2 processes on the host computer.
- Will NOT communicate with other computers on your network.
This guide explains how to further customize your DDS configuration if the above settings are not appropriate for your application, such as:
- Distributing compute across multiple computers.
- Using eprosima Fast RTPS.
Cyclone DDS
By default, MoveIt Pro uses Cyclone DDS. We provide two methods to configure Cyclone DDS:
- Answering "no" to "Use user provided DDS configuration?" in
moveit_pro configure
. MoveIt Pro will configure Cyclone DDS to only talk inside the Docker container and your host computer. - Answering "no" to "Use user provided DDS configuration?" in
moveit_pro configure
and exporting environment variables to enable a distributed computer setup. MoveIt Pro will also configure Cyclone DDS to talk to your specified machines. - Answering "yes" and exporting an environment variable to point to your own Cyclone DDS xml configuration file. MoveIt Pro will use your provided configuration.
For persistent changes, add these environment variables to your ~/.bashrc
rather than entering them in each new terminal.
For Cyclone DDS Option 1, no additional action is required
By default, Option 1 will generate a Cyclone DDS configuration that:
- Will communicate with ROS 2 processes inside the MoveIt Pro docker container.t
- Will communicate with ROS 2 processes on the host computer.
- Will NOT communicate with other computers on your network.
This Cyclone DDS configuration looks like:
<?xml version='1.0' encoding='us-ascii'?>
<CycloneDDS xmlns="https://cdds.io/config" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:schemaLocation="https://cdds.io/config https://raw.githubusercontent.com/eclipse-cyclonedds/cyclonedds/master/etc/cyclonedds.xsd">
<Domain id="any">
<General>
<Interfaces>
<NetworkInterface autodetermine="false" name="lo" />
</Interfaces>
<AllowMulticast>false</AllowMulticast>
</General>
<Discovery>
<ParticipantIndex>auto</ParticipantIndex>
<Peers>
<Peer Address="127.0.0.1" /></Peers>
<MaxAutoParticipantIndex>50</MaxAutoParticipantIndex>
</Discovery>
<Internal>
<!-- Improves the performance of topic subscribers receiving large messages. -->
<SocketReceiveBufferSize min="10MB" />
</Internal>
</Domain>
</CycloneDDS>
This default configuration is for a single PC setup running both the Agent and Robot Drivers.
For Cyclone DDS Option 2, you will need to export the following environment variables on each computer running MoveIt Pro
CYCLONEDDS_NETWORK_INTERFACE
(the name of the network device being used to talk to the other computer(s), e.g.enp0s31f6
). This will likely be different for each computer you configure. You can find the current names of the network interfaces on each system by runningip a
from the command line. The output from this command will be different for the Agent Computer and the Driver Computer.CYCLONEDDS_PEER_ADDRESSES
(a comma delimited list of IP addresses of the computers that should talk to each other, including the computer you are setting up, e.g.192.168.10.10,192.168.10.12
). You will use this same list of IP addresses on each computer you configure.
Example of Cyclone DDS Option 2
Below is an example for setting up a 2 computer configuration. Computer 1 is a low cost computer that will run all our hardware drivers. Computer 2 is a powerful computer that will run our ML inference.
Computer 1 has two network interfaces (one to connect to the internet and another to connect to the Driver Computer), so the network interface information would look similar to this:
$ ip a
1: lo: <LOOPBACK,UP,LOWER_UP> mtu 65536 qdisc noqueue state UNKNOWN group default qlen 1000
link/loopback 00:00:00:00:00:00 brd 00:00:00:00:00:00
inet 127.0.0.1/8 scope host lo
valid_lft forever preferred_lft forever
inet6 ::1/128 scope host
valid_lft forever preferred_lft forever
2: eno1: <BROADCAST,MULTICAST,UP,LOWER_UP> mtu 1500 qdisc fq_codel state UP group default qlen 1000
link/ether 1c:69:7a:0f:3e:75 brd ff:ff:ff:ff:ff:ff
altname enp0s31f6
inet #.#.#.#/24 brd #.#.#.255 scope global dynamic noprefixroute eno1
valid_lft 68323sec preferred_lft 68323sec
inet6 #::#:#:#:#/64 scope link noprefixroute
valid_lft forever preferred_lft forever
3: enp0s31f6: <BROADCAST,MULTICAST,UP,LOWER_UP> mtu 1500 qdisc mq state UP group default qlen 1000
link/ether f4:3a:8c:70:c2:b1 brd ff:ff:ff:ff:ff:ff
inet 192.168.10.10/24 brd 192.168.10.255 scope global noprefixroute enp0s31f6
valid_lft forever preferred_lft forever
inet6 fe80::c8e:a7ff:f36f:1ef4/64 scope link noprefixroute
valid_lft forever preferred_lft forever
Computer 2 uses two wired network interfaces (one to connect to the Computer 1 and another to connect to the robot's Control Box), so its network interface information would look like this:
$ ip a
1: lo: <LOOPBACK,UP,LOWER_UP> mtu 65536 qdisc noqueue state UNKNOWN group default qlen 1000
link/loopback 00:00:00:00:00:00 brd 00:00:00:00:00:00
inet 127.0.0.1/8 scope host lo
valid_lft forever preferred_lft forever
inet6 ::1/128 scope host
valid_lft forever preferred_lft forever
2: enp112s0: <BROADCAST,MULTICAST,UP,LOWER_UP> mtu 1500 qdisc mq state UP group default qlen 1000
link/ether f4:3a:8c:70:c2:b1 brd ff:ff:ff:ff:ff:ff
inet 192.168.10.12/24 brd 192.168.10.255 scope global noprefixroute enp112s0
valid_lft forever preferred_lft forever
inet6 fe80::6a48:1686:19d8:3085/64 scope link noprefixroute
valid_lft forever preferred_lft forever
3: eno1: <BROADCAST,MULTICAST,UP,LOWER_UP> mtu 1500 qdisc pfifo_fast state UP group default qlen 1000
link/ether f4:3a:8c:70:c2:b1 brd ff:ff:ff:ff:ff:ff
altname enp0s31f6
inet 192.10.0.12/24 brd 192.10.0.255 scope global noprefixroute eno1
valid_lft forever preferred_lft forever
inet6 fe80::a6ae:11ff:fe1e:cb89/64 scope link noprefixroute
valid_lft forever preferred_lft forever
Using the example output above, we would export the following environment variables to Computer 1's environment:
CYCLONEDDS_NETWORK_INTERFACE=enp0s31f6
CYCLONEDDS_PEER_ADDRESSES=192.168.10.10,192.168.10.12
And export the following environment variables to Computer 2's environment:
CYCLONEDDS_NETWORK_INTERFACE=enp112s0
CYCLONEDDS_PEER_ADDRESSES=192.168.10.10,192.168.10.12
For Cyclone DDS Option 3, you will need to export the following environment variables (on each computer running Pro, if there are multiple)
CYCLONEDDS_URI
(the location on your host file system of your custom Cyclone DDS config, typically~/.ros/cyclonedds.xml
)
MoveIt Pro will copy the local file system's Cyclone DDS configuration located at CYCLONEDDS_URI
into the Docker container and use this copied configuration.
In our experience, many failures are caused by misconfiguring DDS settings. When launching MoveIt Pro, running ROS 2 commands/nodes on the host computer, running MoveIt Pro on another computer on the network, or running ROS 2 commands/nodes on another computer on the network, we strongly recommend that you check your local environments for any dangling DDS configuration.
You must be certain that the DDS configuration being used by those commands/nodes will function with what is running in your other processes.
FastRTPS
MoveIt Pro also supports Options 1 and 3 for eprosima Fast RTPS (formally FastDDS).
For FastRTPS Option 1, you will need to export the following environment variables
RMW_IMPLEMENTATION=rmw_fastrtps_cpp
(MoveIt Pro will be configured to use Fast RTPS as middleware)
For FastRTPS Option 3, you will need to export the following environment variables (on each computer running Pro, if there are multiple)
RMW_IMPLEMENTATION=rmw_fastrtps_cpp
(MoveIt Pro will be configured to use Fast RTPS as middleware)FASTRTPS_DEFAULT_PROFILES_FILE
(the location on your host file system of your custom Cyclone DDS config, typically~/.ros/cyclonedds.xml
)
You may also set RMW_FASTRTPS_USE_QOS_FROM_XML
to 1 to allow any QoS settings from your specific XML configuration to actually take effect.