Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Bug] Not able to configure zenoh-bridge to only listen for incoming connections #85

Closed
wvergouwenavular opened this issue Feb 29, 2024 · 7 comments · Fixed by #119
Closed
Labels
bug Something isn't working

Comments

@wvergouwenavular
Copy link

Describe the bug

Im not sure if this is a bug, or if it is not clear what configuration we need to achieve what we want to achieve.

We have a wifi network with multiple robots, and each robot runs its own zenoh-bridge-ros2dds process. We would like to be able to run a zenoh bridge locally on a development laptop, and then connect that bridge to a single robot. This works fine when only one robot is online. However, when multiple robots are online in the same network, all robot bridges connect to each other. So they can all access eachothers data. We want to prevent this from happening. So the bridges on the robots should not actively look for other bridges, but instead should just wait for another bridge (from a development laptop) to connect to one of their open ports.

We've tried multiple configuration options, but we can't seem to get to a configuration where the robots ignore each other, without adding extra namespaces on all bridges.

Thank you in advance

To reproduce

We are running the following docker compose service:

zenoh:
image: 'eclipse/zenoh-bridge-ros2dds:release-0.10.1-rc2'
container_name: zenoh
network_mode: host
init: true
privileged: true
environment:
ROS_DISTRO: humble
RMW_IMPLEMENTATION=rmw_cyclonedds_cpp
CYCLONEDDS_URI: "/etc/avular/dds/cyclone_loopback.xml"
ROS_DOMAIN_ID=${ROS_DOMAIN_ID}
command: '-d ${ROS_DOMAIN_ID} -l tcp/192.168.0.1:7447'

We can see the bridge connects to another bridge, which is running a similiar configuration:
[2024-02-29T14:57:22Z INFO zenoh_plugin_ros2dds] Remote bridge 4315b9ff5a51266446e4cd2bb11b13d2 announces Service Server ros_bridge/get_parameter_types
[2024-02-29T14:57:22Z INFO zenoh_plugin_ros2dds::routes_mgr] Route Service Client (ROS:/ros_bridge/get_parameter_types <-> Zenoh:ros_bridge/get_parameter_types) created

And afterwards a lot more topics and services from the other robot follow.

System info

  • Platform: ubuntu 22.04
  • Hardware: Jetson Xavier NX (arm64)
  • eclipse/zenoh-bridge-ros2dds:release-0.10.1-rc2'
@wvergouwenavular wvergouwenavular added the bug Something isn't working label Feb 29, 2024
@wvergouwenavular
Copy link
Author

@btertoolen

@ciandonovan
Copy link

When connecting your client to the server/bridge, use the -m client flag, by default it's set to -m peer. Solved a similar issue for us

@ciandonovan
Copy link

Also try --no-multicast-scouting on the server/bridge

@JEnoch
Copy link
Member

JEnoch commented Mar 1, 2024

As any Zenoh application the bridges have enabled by default 2 scouting mechanisms allowing to discover other Zenoh applications and routers, and possibly automatically connect to those:

If you want to strictly control where your bridges connect to, you have to disable those features.

So the bridges on the robots should not actively look for other bridges, but instead should just wait for another bridge (from a development laptop) to connect to one of their open ports.

For this case, you need to configure you bridge to listen for incoming connections on a chosen port, and to disable all sco{uting mechanisms as such:

{
  plugins: {
    ros2dds: {
      // your ROS2 related configuration
    }
  },
  // zenoh related configuration
  mode: "peer",
  listen: {
    // listen for TCP connections on all interfaces on port 7447
    endpoints: [
      "tcp/0.0.0.0:7447"
    ]
  },
  // disable all scouting, thus only explicit incoming connections on listen endpoint are accepted
  scouting: {
    multicast: {
      enabled: false
    },
    gossip: {
      enabled: false
    }
  }
}

When connecting your client to the server/bridge, use the -m client flag, by default it's set to -m peer. Solved a similar issue for us

In client mode, Zenoh tries at startup to connect to another peer or router, either configured via connect, either discovered via scouting. If it can't establish a connection, it exits after a timeout.
Thus it can work only for a robot that tries to establish a connection to a control infrastructure (or another robot) at startup.
It cannot work for a robot which is waiting for incoming connections. This requires peer mode.

@btertoolen
Copy link

@ciandonovan @JEnoch Thanks for your suggestions!

The config file which disables all scouting indeed seemed to resolve our issue, so that's great.

To me as an outsider it seems a bit counterintuitive that when you configure the bridge to listen to certain endpoints, it also listens to these scouting endpoints which aren't mentioned in the zenoh-plugin-ros2dds repository anywhere (also not in the example configuration for example). I guess it is this way since this functionality is part of the standard zenoh router. I think we have a pretty standard use case so maybe more people will run into this issue. Maybe it makes sense to mention this in the Usage section in the readme.md or somewhere else? I would also be happy to help with a PR for this documentation if you think its useful to add.

@mdxtinkernick
Copy link

Hi this has fixed the issue for us a well - was looking around to try and do this for a while. One thing that doesn't work as hoped is rqt_graph, which only sees the bridge, not the nodes on the robot. I know that's basically what the bridges job is -but is this something that will not be possible at all, or will it be something for the upcoming rmw implementation.

@JEnoch
Copy link
Member

JEnoch commented Apr 11, 2024

To me as an outsider it seems a bit counterintuitive that when you configure the bridge to listen to certain endpoints, it also listens to these scouting endpoints which aren't mentioned in the zenoh-plugin-ros2dds repository anywhere (also not in the example configuration for example). I guess it is this way since this functionality is part of the standard zenoh router. I think we have a pretty standard use case so maybe more people will run into this issue. Maybe it makes sense to mention this in the Usage section in the readme.md or somewhere else? I would also be happy to help with a PR for this documentation if you think its useful to add.

The bridge is by default configured as a Zenoh peer. And that's the default behaviour of a Zenoh peer to perform scouting and automatically try to connect to discovered peers.

Now I realise from your feedbacks that's not a desired behaviour for a robot to automatically connect to any other robot or ROS 2 host it discovers. It would make more sense for the bridge to act in the same way than a Zenoh router, just listening on TCP port 7447 and waiting for incoming connections.
BTW, that's how rmw_zenoh will behave by default: a Zenoh router deployed for external communications, and listening on TCP port `7447.

We'll do a PR for this shortly.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

Successfully merging a pull request may close this issue.

5 participants