Class DomainBridge

Class Documentation

class DomainBridge

Bridge ROS entities across different domains.

This class is responsible for forwarding ROS messages across different ROS domains. Topics can be bridged from one domain to another by calling bridge_topic().

Internally, the domain bridge creates a ROS node for each domain ID involved in the bridge. It is up to the user to provide the execution model, which is used for processing subscription callbacks for example. A user can add the bridge to an executor of their choice with add_to_executor(). Optionally, the user can configure callback groups per bridged topic via TopicBridgeOptions when calling bridge_topic().

Example usage:

 ++
// Create a domain bridge
domain_bridge::DomainBridge domain_bridge;

// Bridge one or more topics
domain_bridge.bridge_topic("/clock", "rosgraph_msgs/msg/Clock", 5, 10);
domain_bridge.bridge_topic("image", "sensor_msgs/msg/Image", 5, 10);
// ...

// Create an executor and add the bridge nodes to it
rclcpp::executors::SingleThreadedExecutor executor;
domain_bridge.add_to_executor(executor);

// Start executing callbacks, hence forwarding messages across the bridge
executor.spin();

Public Functions

explicit DomainBridge(const DomainBridgeOptions &options = DomainBridgeOptions())

Constructor.

explicit DomainBridge(const DomainBridgeConfig &config)

Constructor from DomainBridgeConfig.

Constructor that also creates bridges based on the passed configuration.

DomainBridge(DomainBridge &&other)

Move constructor.

DomainBridge &operator=(DomainBridge &&other) = default

Move assignment operator.

~DomainBridge()

Destructor.

DomainBridgeOptions get_domain_bridge_options() const

Get the options for this domain bridge.

void add_to_executor(rclcpp::Executor &executor)

Add the bridge to an executor.

When the executor is running ROS traffic will be bridged between domains. Only topics registered with bridge_topic() will have their messages forwarded.

This method will add all nodes associated with this bridge to the provided executor.

Parameters:

executor – The executor to add this domain bridge to.

void bridge_topic(const std::string &topic, const std::string &type, size_t from_domain_id, size_t to_domain_id, const TopicBridgeOptions &options = TopicBridgeOptions())

Bridge a topic from one domain to another.

Parameters:
  • topic – Name of the topic to bridge.

  • type – Name of the topic type (e.g. “example_interfaces/msg/String”)

  • from_domain_id – Domain ID the bridge will use to subscribe to the topic.

  • to_domain_id – Domain ID the bridge will use to publish to the topic.

  • options – Options for bridging the topic.

void bridge_topic(const TopicBridge &topic_bridge, const TopicBridgeOptions &options = TopicBridgeOptions())

Bridge a topic from one domain to another.

Parameters:
  • topic_bridge – Struct containing info about the topic to bridge.

  • options – Options for bridging the topic.

template<typename ServiceT>
void bridge_service(const std::string &service, size_t from_domain_id, size_t to_domain_id, const ServiceBridgeOptions &options = ServiceBridgeOptions())

Bridge a service from one domain to another.

Parameters:
  • service – Name of the service to be bridged.

  • from_domain_id – Domain id where there is a service server to be bridged.

  • to_domain_id – Domain id where we want to make request to the bridged service.

  • options – Options for bridging the topic.

std::vector<TopicBridge> get_bridged_topics() const

Get bridged topics.

Returns:

Topic bridges created by bridge_topic().