Multi-Robot Architecture

A natural evolution of ROS2 architectures consists in deploying multi-robot solutions. However, several robots will necessarily generate duplicated needs in topic connections. Typically, each robot should have its own mounted laser. The difficulty in multi-robot architectures is to control message isolation.

ROS2 Basic Solution

ROS2 natively supports two solutions to isolate topics: namespaces and domain IDs. Namespace, on one hand, applies to topic names to differentiate topic ownership or context. For instance, for laser scans, we can declare robot1 and robot2, and scan topics will appear as robot1/scan and robot2/scan. Note that namespaces should also affect frame IDs to differentiate frames attached to robot1 from those attached to robot2.

The main inconvenience of the namespace solution is that everything is visible to every nodes on every machines, with an impact on the network discovery process. On the other hand, domain IDs allow isolated topics with dedicated ports on the network interface. The counterpart is that robots evolving with their own domain IDs cannot communicate with each other.

This tutorial proposes a solution to leverage the domain ID counterpart. For more details on the namespace solution, you can refer to the large projects section in the official documentation. More solutions are proposed in our multibot package.

Multi-Domain IDs

The solution is trivial. It consist in isolate robot "private" information in its own domain ID, and to use a second, shared domaim ID for information to share with the other robots.

However, at some point we will require some node capable to communicate on the both domains. In fact, it is impossible in ROS2. The solution consist in defining a process based on several nodes each attached to a different domain ID.

So:

  1. Define a process with tow nodes, one on each domain ID.
  2. Spin each node independantly.

ROS2 tools for multi-node processes

To do that, we need to manipulate three ROS2 classes. The well-known Node, the Context defining a frame for nodes (typically a link to a domain), and the Executor in charge of managing events (subscriptions to timers and topics).

By default, the Context and the Executor are globally defined, with hidden calls to them.

Context, Node and Executor

The idea is to create a Context for each domain ID we want to reach (different from the default one, i.e. the one defined through an environment variable).

from rclpy.context import Context
context42 = Context()
context42.init(domain_id= 42)            

Then, we can define a node attached to this specific context:

node42= Node( f"nodeOn42", context=context42 )

This node will subscribe and publish on the domain ID \(42\).

Finally, since we want to manage objects defined with several nodes, we need to 'spin' them using a ROS2 executor. The simplest way is to use the globally defined one.

rclpy.init()
executor= rclpy.get_global_executor()

Then, attach all the nodes to the executor and spin them (process them indefinitely).

executor.add_node( node1 )
executor.add_node( node2 )
...
executor.add_node( node42 )

# Infinite loop:
executor.spin()

Don forget a clean end:

node1.destroy_node()
node2.destroy_node()
...
node42.destroy_node()
rclpy.shutdown()

Example of publisher

Here a simple example publishing a short mesage on \(2\) topics defined on \(2\) ROS2 domains.

#!/usr/bin/python3
import rclpy
from rclpy.node import Node
from rclpy.context import Context
from std_msgs.msg import String

def main():
    tester= Pub()
    tester.process()

class StringCallBack():
    def __init__(self, pub, msg):
        self._publisher= pub
        self._msg= String()
        self._msg.data= msg

    def __call__(self):
        self._publisher.publish( self._msg )

class Pub():
    def __init__(self):
        pass

    def process(self):
        # Ros initialization
        rclpy.init()
        executor= rclpy.get_global_executor()

        self._nodes= []
        self._test_publishers= []

        for domId, msg, freq in zip( [14, 42], ['salut', 'nounou'], [2.0, 0.3] ) :
            rosContext = Context()
            rosContext.init(domain_id= domId)
            node= Node( f"multipub{domId}", context=rosContext )
            publisher= node.create_publisher( String, 'test', 10 )
            node.create_timer( freq, StringCallBack( publisher, msg ) )

            executor.add_node( node )
            self._nodes.append( node )

        # Infinite loop:
        executor.spin()

        # Clean stop:
        for node in self._nodes :
            node.destroy_node()
        rclpy.shutdown()

if __name__ == '__main__':
    main()

Example of subscriber

And the subscriber capable of merging the mesages.

#!/usr/bin/python3
import rclpy
from rclpy.node import Node
from rclpy.context import Context
from std_msgs.msg import String

def main():
    tester= Sub()
    tester.process()

class StringCallBack():
    def __init__( self, domainId ):
        self.domainId= domainId

    def __call__(self, aString):
        print( f"{aString.data} (from {self.domainId})" )

class Sub():
    def __init__(self):
        pass

    def process(self):
        # Ros initialization
        rclpy.init()
        executor= rclpy.get_global_executor()

        self._nodes= []
        self._test_publishers= []

        for domId in [14, 42] :
            rosContext = Context()
            rosContext.init(domain_id= domId)
            node= Node( f"test{domId}", context=rosContext )
            node.create_subscription( String, "test", StringCallBack(domId), 10 )

            executor.add_node( node )
            self._nodes.append( node )

        # Infinite loop:
        executor.spin()

        # Clean stop:
        for node in self._nodes :
            node.destroy_node()
        rclpy.shutdown()

if __name__ == '__main__':
    main()