ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

USING ros2 offline (ROS_LOCALHOST_ONLY=1)

asked 2020-11-07 20:31:20 -0600

Hi,

I'm trying to do a demo of mapping a large building with ROS2 Foxy, Slam Toolbox and a Rover Pro. I'm starting inside an office connected to wifi and then moving down a hallway where I lose wifi connection. If I have ROS_LOCALHOST_ONLY=0 then I have several nodes crash with error message tev: ddsi_udp_conn_write to udp/10.0.3.119:58679 failed with retcode: -1

image description

I then set ROS_LOCALHOST_ONLY=1 and am able to drive outside of wifi coverage but RVIZ2 fails to open with the error failed to find a free participant index for domain 0 so I am not able to see the map I'm creating.

image description

Here is my ROS2 doctor --report

NETWORK CONFIGURATION ether
: 1c:69:7a:00:c8:04 device : eno1 flags : 4099<up,broadcast,multicast> mtu
: 1500 inet : 127.0.0.1 inet4 : ['127.0.0.1'] inet6 : ['::1'] netmask : 255.0.0.0 device
: lo flags : 73<up,loopback,running> mtu
: 65536 inet : 10.0.3.119 inet4 : ['10.0.3.119'] ether
: d0:c6:37:08:eb:ca inet6 : ['fe80::eef9:c514:2059:e7cb'] netmask : 255.255.248.0 device : wlp0s20f3 flags : 4163<up,broadcast,running,multicast> mtu : 1500 broadcast : 10.0.7.255 inet : 10.10.0.2 inet4 : ['10.10.0.2'] ether
: 9e:39:0f:d3:8b:c9 inet6 : ['fe80::9c39:fff:fed3:8bc9'] netmask
: 255.255.255.0 device : ztppirst4c flags : 4163<up,broadcast,running,multicast> mtu : 2800 broadcast : 10.10.0.255

PACKAGE VERSIONS builtin_interfaces : required=1.0.0, local=1.0.0 nav2_planner
: required=0.4.5, local=0.4.3 action_tutorials_cpp
: required=0.9.3, local=0.9.3 nav2_gazebo_spawner
: required=0.4.5, local=0.4.3 rosidl_typesupport_introspection_cpp
: required=1.1.0, local=1.0.1 actionlib_msgs
: required=2.0.3, local=2.0.3 ament_uncrustify
: required=0.9.5, local=0.9.5 ament_cmake_core
: required=0.9.7, local=0.9.6 cartographer_ros
: required=1.0.9002, local=1.0.9001 sdl2_vendor
: required=2.4.1, local=2.4.1 pendulum_control
: required=0.9.3, local=0.9.3 resource_retriever
: required=2.3.3, local=2.3.2 nav_msgs : required=2.0.3, local=2.0.3

launch_testing_ament_cmake
: required=0.10.3, local=0.10.2 rosbag2_compression
: required=0.3.5, local=0.3.4 rcl_action
: required=1.1.9, local=1.1.7 rosidl_generator_cpp
: required=1.1.0, local=1.0.1 ament_cmake_target_dependencies
: required=0.9.7, local=0.9.6 rclcpp_components
: required=2.2.0, local=2.1.0 nav2_costmap_2d
: required=0.4.5, local=0.4.3 ros2lifecycle
: required=0.9.7, local=0.9.7 lifecycle
: required=0.9.3, local=0.9.3 tinyxml_vendor
: required=0.8.0, local=0.8.0 gazebo_msgs
: required=3.5.0, local=3.5.0 cv_bridge
: required=2.2.1, local=2.2.1 ament_lint_auto
: required=0.9.5, local=0.9.5 nav2_map_server
: required=0.4.5, local=0.4.3 ament_cmake_flake8
: required=0.9.5, local=0.9.5 rqt_py_common ...

(more)
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
4

answered 2020-11-11 03:40:00 -0600

eboasson gravatar image

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:

  • needs a set of well-known port numbers at which to reach the processes, which is where this thing called "participant index" shows up in the specification;
  • needs to actually send packets to all of those ports periodically if it is to deal correctly with all nasty edge cases with flaky networks, and the larger that set the worse those bursts become (this is just a consequence of how the DDSI-RTPS specification works), which, combined with a bit of ancient history, resulted in limiting it to 10 by default;
  • hits that limit ...

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 ... (more)

edit flag offensive delete link more

Comments

If you were to setup Cyclone as in the last full xml file you listed, do you have any things to lookout for if choosing lo as the NetworkInterface and false for AllowMulticast? I assume this is not "breaking" necessarily, but doesn't ROS depend on multicast?

hapy-capy gravatar image hapy-capy  ( 2023-01-04 16:31:04 -0600 )edit
1

answered 2020-11-08 05:19:32 -0600

duck-development gravatar image

You clould start an AP an the robot. And connect direct to the robot.

    ROS_LOCALHOST_ONLY=0

And rviz should work properly.

edit flag offensive delete link more

Comments

yes, hostapd with static ip address will be a temporary workaround solution. I use a WIFi USB stick as secondary wireless interface for off-road usage.

ChriMo gravatar image ChriMo  ( 2020-11-08 15:16:25 -0600 )edit

maybe a dummy interface will help

sudo ip link add dummy0 type dummy

sudo ip addr add 10.11.99.1/24 dev dummy0

I've never tried it with dds

ChriMo gravatar image ChriMo  ( 2020-11-08 15:25:59 -0600 )edit

How do I tell ROS2 to use a certain interface? In ROS1 there was the variable ROS_IP and ROS_MASTER_URI, but from looking at this thread it sounds like that is no longer the case. https://github.com/ros2/ros2/issues/798

FYI I have a VPN setup to provide a static and persistent interface to point ROS2 to. So now I just need to know how to tell ROS2 to use it.

shoemakerlevy9 gravatar image shoemakerlevy9  ( 2020-11-10 15:30:35 -0600 )edit
1

You may look at https://fast-dds.docs.eprosima.com/en....

Write your xml and export the path

  export FASTRTPS_DEFAULT_PROFILES_FILE=path/to/

https://fast-dds.docs.eprosima.com/en...

duck-development gravatar image duck-development  ( 2020-11-10 16:16:40 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2020-11-07 20:31:20 -0600

Seen: 5,449 times

Last updated: Nov 08 '20