Running MoveIt Pro as a Distributed System
By default, MoveIt Pro is configured to run on a single computer.
However, in some cases it can be useful to distribute the computational load across multiple computers (e.g., hardware drivers or perception modules).
When using multiple computers it is important to keep in mind that all of them must share a network and have compatible DDS configurations to ensure fast and robust communication via ROS.
In the event that a multiple computer setup is preferred, there are a few configuration changes that must be made.
Configuring CycloneDDS for Multiple PC setup
Note
The following section provides basic instructions on how to configure DDS settings for a two PC setup, one running the Agent and one running the Robot Drivers. For more information, please refer to this guide on Configuring DDS for MoveIt Pro.
To enable interprocess communication between machines in your ROS network, you must define the following variables in the .env
file.
CYCLONEDDS_NETWORK_INTERFACE
CYCLONEDDS_PEER_ADDRESSES
The values to use for CYCLONEDDS_NETWORK_INTERFACE
and CYCLONEDDS_PEER_ADDRESSES
depend on the configuration of the network interfaces the Agent Computer and the Driver Computer use to communicate with each other.
- For each system,
CYCLONEDDS_NETWORK_INTERFACE
needs to be set to the name of the network interface which is used to connect to the ROS network. - For each system,
CYCLONEDDS_PEER_ADDRESSES
needs to be set to a comma-separated list containing the IP addresses of the Agent Computer and Driver Computer.
You can find the current names of the network interfaces on each system by running ip a
from the command line. The output from this command will be different for the Agent Computer and the Driver Computer.
For example, suppose our system consists of two computers:
- An “Agent Computer” which runs MoveIt Pro.
- A “Driver Computer” running a real-time operating system for communicating with the hardware.
The Agent Computer 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
The Driver Computer uses two wired network interfaces (one to connect to the Agent Computer 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 append the following entries to the .env
file on the Agent Computer:
CYCLONEDDS_NETWORK_INTERFACE=enp0s31f6
CYCLONEDDS_PEER_ADDRESSES=192.168.10.10,192.168.10.12
And append the following entries to the .env
file on the Driver Computer:
CYCLONEDDS_NETWORK_INTERFACE=enp112s0
CYCLONEDDS_PEER_ADDRESSES=192.168.10.10,192.168.10.12
Alternatively, it is possible to use the host system’s Cyclone DDS configuration.
To do so, it is necessary to set two variables in your .env
file.
Configure usage of the host config by setting USE_HOST_DDS=true
and mount the host configuration file into the MoveIt Pro Docker containers by setting CYCLONEDDS_URI=<path_to_your_host_configuration_files>
.
Configuring Cameras for Multiple PC setup
Suppose you are running the MoveIt Pro Agent on a machine (the Agent machine) and the robot drivers on another (the Driver machine), the cameras mentioned in cameras.yaml
are launched by default by the MoveIt Pro Agent.
Therefore, the cameras should be connected to the Agent machine.
If the cameras need to be connected to the Drivers machine (for example, due to wiring constraints), apply these changes to your configuration package so that MoveIt Pro will detect and launch the cameras from the Drivers service:
- Disable the camera from being launched by the agent launch file by setting the parameter
use
toFalse
in thecameras.yaml
file.
- wrist_mounted_camera:
camera_name: "wrist_mounted_camera"
type: "realsense"
use: False
serial_no: "204222061127"
device_type: "D415"
framerate: 6
image_width: 640
image_height: 480
enable_pointcloud: True
- Launch the camera with the robot drivers by adding the following lines of code in the file specified under the
hardware.robot_driver_persist_launch_file
parameter in theconfig.yaml
file.
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch_ros.actions import Node
from moveit_studio_utils_py.launch_common import get_launch_file
from moveit_studio_utils_py.system_config import (
SystemConfigParser,
)
def generate_launch_description():
system_config_parser = SystemConfigParser()
# Load camera details from the file listed under `hardware.camera_config` parameter in config.yaml
cameras_config = system_config_parser.get_cameras_config()
included_launch_files = []
nodes_to_launch = []
camera_frames = []
for camera in cameras_config:
camera = camera[next(iter(camera))]
camera_frames.append(camera["camera_name"] + "_color_frame")
# The Realsense Node wants a string instead of bool for "enable_pointcloud"
enable_pointcloud = "false"
if camera["enable_pointcloud"]:
enable_pointcloud = "true"
# Launch the Realsense camera drivers with each camera settings.
included_launch_files.append(
IncludeLaunchDescription(
get_launch_file("realsense2_camera", "launch/rs_launch.py"),
launch_arguments={
"serial_no": "'" + str(camera["serial_no"]) + "'",
"pointcloud.enable": enable_pointcloud,
"device_type": camera["device_type"],
"camera_name": camera["camera_name"],
"base_frame_id": camera["camera_name"] + "_link",
# All 3 params (fps/width/height) must be set
"depth_module.profile": f"{camera['image_width']}x{camera['image_height']}x{camera['framerate']}",
"rgb_camera.profile": f"{camera['image_width']}x{camera['image_height']}x{camera['framerate']}",
"pointcloud.ordered_pc": "true",
"decimation_filter.enable": "false",
}.items(),
)
)
return LaunchDescription(included_launch_files + nodes_to_launch)