ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
That looks like Cyclone DDS being unhappy ... 😔
The CYCLONEDDS_URI environment variable can be set to a list of XML file(s) and/or embedded XML fragments to configure Cyclone DDS, and there you can configure the network interface to use, as well as deal with the pesky "failed to find a free participant index".
Use the CycloneDDS/Domain/General/NetworkInterfaceAddress element to specify either the name of the interface, or the IP address of the host on that interface, or (for IPv4 networks) the network address (so the host bits cleared).
For the "participant index" thing: it really prefers multicast for discovery, but the default configuration of a Linux loopback interface (at least on some distributions) falsely claims not to support multicast ... because of that it falls back to unicast discovery, but then it:
That limit can be raised by setting
CycloneDDS/Domain/Discovery/MaxAutoParticipantIndex
On Ethernet/WiFi you always have multicast and this problem doesn't exist. On WiFi you do have to make sure you avoid using multicast for data, and I don't know whether the auto-detection of wired vs WiFi will work if there is a VPN in between. So to be safe, you might want to limit the use of multicast to the initial discovery traffic only, by setting
CycloneDDS/Domain/General/AllowMulticast
to "spdp" (for Simple Participant Discovery Protocol)
For example, if you do have working multicast and there's WiFi behind a VPN:
<?xml version="1.0" encoding="UTF-8" ?>
<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>
<NetworkInterfaceAddress>vpn</NetworkInterfaceAddress>
<AllowMulticast>spdp</AllowMulticast>
</General>
</Domain>
</CycloneDDS>
or if you want to avoid multicast altogether (most of this is set automatically when the interface doesn't support multicast, but if you specifically want to avoid multicast on an interface that does support it, you need to do this yourself):
<?xml version="1.0" encoding="UTF-8" ?>
<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>
<NetworkInterfaceAddress>lo</NetworkInterfaceAddress>
<AllowMulticast>false</AllowMulticast>
</General>
<Discovery>
<ParticipantIndex>auto</ParticipantIndex>
<MaxAutoParticipantIndex>30</NetworkInterfaceAddress>
<Peers>
<Peer address="localhost"/>
</Peers>
</Discovery>
</Domain>
</CycloneDDS>
Finally, as I remarked above, you can also put XML fragments in that environment variable, and then you're allowed make some abbreviations: (1) skipping the two top-level elements, (2) abbreviating names to the shortest unique prefix and (3) replacing all closing tags by "". So the first could also be done by
export CYCLONEDDS_URI="<Gen><Net>vpn</><Allow>spdp</></>"
And as a footnote to the final remark: do see https://github.com/eclipse-cyclonedds/cyclonedds/#configuration and see if your editor understands the XSD file that is referenced.