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

ROS2 foxy eProsima Fast RTPS communication between Docker ubuntu container and Windows host [10508] #1698

Closed
anastasiapan opened this issue Jan 20, 2021 · 26 comments

Comments

@anastasiapan
Copy link

anastasiapan commented Jan 20, 2021

Currently I have ROS2 foxy on a linux docker container and what I want to do is to publish and subscribe from the container to Windows side and the other way around as well. The Ros middleware interface I am using right now is eProsima Fast RTPS. Right now I am testing with ros2 examples (minimal publisher and minimal subscriber (https://index.ros.org/r/examples/) . I have tried to do this between two separate containers and it just works out of the box. I have also tried to set an initial peers xml to fix it but I am very new to DDS so I might be missing something there.

Expected Behavior

To be able to publish and subscribe to and from host to Docker container

Current Behavior

The data published from the docker container are not visible from the Windows side.

Steps to Reproduce

  1. Install ROS2 on Windows (https://index.ros.org/doc/ros2/Installation/Foxy/Windows-Development-Setup/). The DDS product installed is by default eProsima Fast RTPS
  2. Build and run ros2 docker image (foxy-ros-base from https://hub.docker.com/_/Ros)
  3. Try to publish and subscribe from container to Windows host like this:
    On the Docker container:
    ros2 run demo_nodes_py talker
    On Windows host:
    ros2 run demo_nodes_py listener

System information

Additional resources

  • XML profiles file
    I named it DEFAULT_FASTRTPS_PROFILES.xml. I tried to put it in the container, in my windows workspace and in both.
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="ROS2_profile" is_default_profile="true">
        <rtps>
            <builtin>
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>host.docker.internal</address>
                            <port>7412</port>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
        </rtps>
    </participant>
</profiles>
@wl2776
Copy link

wl2776 commented Feb 4, 2021

I observe similar issue. Two ROS Foxy installations don't see each other.

One was installed from sources into a docker container, and another - from Debian packages on linux host.

Details are in these two questions:

https://answers.ros.org/question/370595/ros2-foxy-nodes-cant-communicate-through-docker-container-border/
https://stackoverflow.com/questions/65900201/troubles-communicating-with-ros2-node-in-docker-container

@anastasiapan
Copy link
Author

@wl2776 I have found a solution for that but it is with Cyclone DDS (eclipse-cyclonedds/cyclonedds#677). I assume you can have a similar configuration for fast dds too.

@eProsima eProsima deleted a comment from wl2776 Feb 6, 2021
@richiware
Copy link
Member

richiware commented Feb 9, 2021

First, thanks for the reporting. We usually work with Docker containers, but not with that kind of combination. We were testing your environment and, as you pointed to, some extra configuration should be added to FastDDS. Only for reminder, to configure Fast-DDS there are two ways of telling a ROS 2 application which XML to use :

  • Placing your XML file in the running directory under the name DEFAULT_FASTRTPS_PROFILES.xml.
  • Setting environment variable FASTRTPS_DEFAULT_PROFILES_FILE to contain the path to your XML file (relative to the working directory).

Before configuring Fast-DDS you need to know this information: the IP of your Windows host (the public IP of your local network) and select two ports to be used by Fast-DDS inside the Docker container (these ports cannot be used by other application in your Windows host).

In my testing environment the public IP of my Windows host is 192.168.1.133, and the ports I selected are 7414 and 7415. Here you have the XML I used to make the communication works. The XML comes with comments explained the purpose of each part of the XML.

<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="ROS2_profile" is_default_profile="true">
        <rtps>
            <builtin>
                <!-- This locator is used to tell remote participants where
                they are able to discover me.
                The participant in the Windows host will try to find me in
                192.168.1.133:7414.
                Only setting mettatraffic unicast locators, we are disabling
                multicast communicatins -->
                <metatrafficUnicastLocatorList>
                    <locator>
                        <udpv4>
                            <address>192.168.1.133</address>
                            <port>7414</port>
                        </udpv4>
                    </locator>
                </metatrafficUnicastLocatorList>
                <!-- This locator is used to find remote participants.
                In this case Fast-DDS will try unicast communications
                with the participant in the Windows host.-->
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>192.168.1.133</address>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
            <!-- This locator is used to configure where the readers will
            be listeing and to tell remote participants where
            they are able to send user data.
            Docker container particpant's endpoints will be listening 
            in 192.168.1.133:7415. -->
            <defaultUnicastLocatorList>
                <locator>
                    <udpv4>
                        <address>192.168.1.133</address>
                        <port>7415</port>
                    </udpv4>
                </locator>
            </defaultUnicastLocatorList>
        </rtps>
    </participant>
</profiles>

Remember mapping the selected ports when creating the docker container.

 docker run -ti --rm -p 7414:7414/udp -p 7415:7415/udp  DOCKER_IMAGE

I hope this is helpful for you.

@richiware richiware changed the title ROS2 foxy eProsima Fast RTPS communication between Docker ubuntu container and Windows host ROS2 foxy eProsima Fast RTPS communication between Docker ubuntu container and Windows host [10508] Feb 9, 2021
@wl2776
Copy link

wl2776 commented Feb 9, 2021

I have additional points:

  1. Proposed solution is a temporary palliative, since another ROS2 node in another ROS domain, launched in already running container, would not be seen (I mean, docker exec ${container_id} bash -c "ROS_DOMAIN_ID=new_domain ros2 run blah-blah-blah")
  2. I observe this (mis)behavior with Ubuntu hosts too, not only Windows. It was reproduced several times in different real and virtual PCs
  3. If I launch two containers from the same image on the same host, they also don't communicate.

@MiguelCompany
Copy link
Member

@wl2776 If you are using the ROS 2 Foxy binaries, and depending on your configuration, this may be related to #1633, which has already been solved if you build foxy sources.

@MiguelCompany
Copy link
Member

And, by definition, nodes on different domains should NOT communicate. That is the purpose of the domain id.

@wl2776
Copy link

wl2776 commented Feb 9, 2021

I clarify again.
SAME domain ID, I understand its purpose.

Container based on Ubuntu 18.04, ROS2 foxy is built from sources (https://hub.docker.com/repository/docker/wl2776/nvidia-ros it has ROS_DOMAIN_ID=142). I've also tried building another image, based on FROM ubuntu:bionic (dockerfile) with the same result.

Ubuntu 20.04 host, two ROS2 foxy installations: from Debian packages and from sources.

Talker and listener nodes from standard examples. One node is running in the container, another - on host.

No communication between talker and listener when all nodes use FastRTPS.

@richiware
Copy link
Member

I've tested again using your ROS_DOMAIN_ID. In my case there is communication between talker and listener.

talker_listener

Right side is the docker container and left side is the windows host. I've used the provided XML earlier. Do you have a clue which difference could be between your environment and mine?

@wl2776
Copy link

wl2776 commented Feb 9, 2021

I've used Linux host and did not use XML file with additional configuration.
I've also run containers with --net host.

The last point is important.
Listener has heard "hello"s only without --net host.

@anastasiapan
Copy link
Author

anastasiapan commented Feb 10, 2021

First, thanks for the reporting. We usually work with Docker containers, but not with that kind of combination. We were testing your environment and, as you pointed to, some extra configuration should be added to FastDDS. Only for reminder, to configure Fast-DDS there are two ways of telling a ROS 2 application which XML to use :

  • Placing your XML file in the running directory under the name DEFAULT_FASTRTPS_PROFILES.xml.
  • Setting environment variable FASTRTPS_DEFAULT_PROFILES_FILE to contain the path to your XML file (relative to the working directory).

Before configuring Fast-DDS you need to know this information: the IP of your Windows host (the public IP of your local network) and select two ports to be used by Fast-DDS inside the Docker container (these ports cannot be used by other application in your Windows host).

In my testing environment the public IP of my Windows host is 192.168.1.133, and the ports I selected are 7414 and 7415. Here you have the XML I used to make the communication works. The XML comes with comments explained the purpose of each part of the XML.

<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="ROS2_profile" is_default_profile="true">
        <rtps>
            <builtin>
                <!-- This locator is used to tell remote participants where
                they are able to discover me.
                The participant in the Windows host will try to find me in
                192.168.1.133:7414.
                Only setting mettatraffic unicast locators, we are disabling
                multicast communicatins -->
                <metatrafficUnicastLocatorList>
                    <locator>
                        <udpv4>
                            <address>192.168.1.133</address>
                            <port>7414</port>
                        </udpv4>
                    </locator>
                </metatrafficUnicastLocatorList>
                <!-- This locator is used to find remote participants.
                In this case Fast-DDS will try unicast communications
                with the participant in the Windows host.-->
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>192.168.1.133</address>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
            <!-- This locator is used to configure where the readers will
            be listeing and to tell remote participants where
            they are able to send user data.
            Docker container particpant's endpoints will be listening 
            in 192.168.1.133:7415. -->
            <defaultUnicastLocatorList>
                <locator>
                    <udpv4>
                        <address>192.168.1.133</address>
                        <port>7415</port>
                    </udpv4>
                </locator>
            </defaultUnicastLocatorList>
        </rtps>
    </participant>
</profiles>

Remember mapping the selected ports when creating the docker container.

 docker run -ti --rm -p 7414:7414/udp -p 7415:7415/udp  DOCKER_IMAGE

I hope this is helpful for you.

Thank you for your answer. I tried this configuration but it did not work. It is very similar to the solution I found using Cyclone so if I directly compare them assume I also need some more configurations to my Dockerfile possibly an appropriate xml for the FASTRTPS profile inside the container too.

@wl2776
Copy link

wl2776 commented Feb 11, 2021

There is another user of https://answers.ros.org having the same issue.
https://answers.ros.org/question/370595/ros2-foxy-nodes-cant-communicate-through-docker-container-border/?comment=371588#post-id-371588

Did you manage to reproduce it?

The important point is running container with --net host, that is turn off its network isolation

@anastasiapan
Copy link
Author

--net host is not doing it for me but I have switched to Cyclone for now. Even though I am considering ditching the Windows setup for good since it gives me many problems due to the fact that I have to disable multicast to make it discoverable. The reason I am not closing the issue is that I have not actually found a solution for fast dds.

@richiware
Copy link
Member

@anastasiapan Did you use my XML only inside the Docker container? The windows host's application doesn't needed. And the IP on the XML should be change by you Windows host's public local network IP. Did you also change the ports? Are you using a particular ROS_DOMAIN_ID?

@wl2776 I haven't time to test. I will try this afternoon.

@wl2776
Copy link

wl2776 commented Feb 11, 2021

@richiware, thanks.
Again, short summary.

Host: Ubuntu 20.04, two ROS2 installations: from sources and from Debian packages (issue is reproduced in both)
Container: based on Ubuntu 18.04, ROS2 installed from sources (https://hub.docker.com/repository/docker/wl2776/nvidia-ros).
Container runs without network isolation (--net host).
No additional XML configurations.
The listener doesn't hear "hello"s from the talker, if one of them runs in the container and both use FastDDS
If at least one of nodes is switched to CycloneDDS (host or container, no matter), the issue disappears.

@anastasiapan
Copy link
Author

@richiware Ok it was the ROS_DOMAIN_ID after all. It works with this config and with setting the correct ROS_DOMAIN_ID.Thank you!

@richiware
Copy link
Member

@wl2776 I've tested your case. I've found what is happening. The last releases of Fast-DDS come with SharedMemory transport by default. Using --net=host implies both DDS participants believe they are in the same machine and they try to communicate using SharedMemory instead of UDP. We will implement a mechanism to detect this kind of situation. Meanwhile, I can give you two solutions:

  1. Using a XML to disable SharedMemory transport in one of the DDS participants.
<?xml version="1.0" encoding="UTF-8" ?>
    <profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles" >
        <transport_descriptors>
            <transport_descriptor>
                <transport_id>CustomUdpTransport</transport_id>
                <type>UDPv4</type>
            </transport_descriptor>
        </transport_descriptors>

        <participant profile_name="participant_profile" is_default_profile="true">
            <rtps>
                <userTransports>
                    <transport_id>CustomUdpTransport</transport_id>
                </userTransports>

                <useBuiltinTransports>false</useBuiltinTransports>
            </rtps>
        </participant>
    </profiles>
  1. Enable SharedMemory between host and container. For this you should share /dev/shm:
docker run -ti --net host -v /dev/shm:/dev/shm <DOCKER_IMAGE>

Also, both applications should be run with the same UID. In my case, my docker container's user is root (UID=0). Then I had to run the host application as root.

I hope this helps you.

@richiware
Copy link
Member

@richiware Ok it was the ROS_DOMAIN_ID after all. It works with this config and with setting the correct ROS_DOMAIN_ID.Thank you!

@anastasiapan Which ROS_DOMAIN_ID is working for you and which not? I believed that XML should work with any ROS_DOMAIN_ID. I want to check that.

Thanks

@wl2776
Copy link

wl2776 commented Feb 12, 2021

Yes, the first variant with additional XML, disabling shared memory, works well.

I haven't tested sharing /dev/shm

I've also created another separate issue, because I believe that my case differs from the case of anastasiapan.

@TSC21
Copy link

TSC21 commented Feb 12, 2021

@richiware I am exactly facing the same issue, but unfortunately I am not able to make it work with neither the solutions above. To note that I a container with docker run --rm -it --name px4-sitl --net=host and then I am trying to list the topics in the host with ros2 topic list and none of the topics started in the container appear listed: (the curious thing is that neither they appear listed in the container)

$ros2 topic list
/parameter_events
/rosout

@anastasiapan what is a "correct" ROS_DOMAIN_ID?

@TSC21
Copy link

TSC21 commented Feb 12, 2021

@richiware I got the problem solved after rebooting the host and the second solution does seem to work (though I see a huge lag in the simulated camera stream when showing it in Rviz). Trying the UDP approach and while starting rviz2, I am getting:

2021-02-12 15:01:42.567 [XMLPARSER Error] Error opening '/home/nuno/fastrtps-profile.xml' -> Function loadXML
2021-02-12 15:01:42.567 [XMLPARSER Error] Error parsing '/home/nuno/fastrtps-profile.xml' -> Function loadXMLFile

Any idea?

@anastasiapan
Copy link
Author

Ok so what I did was

  1. Use the xml config inside my container and not in host machine - with my Windows public network ip
  2. Run the docker container interactively and also publishing the ports docker run -it --rm -p 7414:7414/udp -p 7415:7415/udp image
  3. I dont use any particular ROS_DOMAIN_ID I just tested with 42 (from this example https://discourse.ros.org/t/how-to-run-example-talker-listener-on-2-machines-with-different-ipaddr/2106/2)

I do not know though what configuration is making it work - I have a feeling that step 3 might be redundant but I did not test it.

@TSC21
Copy link

TSC21 commented Feb 22, 2021

@richiware I don't think this issue should be closed to be honest. My experience so far has been quite negative when using FastDDS inside docker containers with ROS 2. Sometimes it works with shared memory, sometimes it doesn't. Same with UDP. And I keep seeing a really high latency on camera topics (being published by gazebo_ros) when I eventually get it to work (for example, topics that are supposed to be published at 15hz, when using ros2 topic hz I get them at 3/4hz on the host side.

This should definitely be more investigated IMHO.

@EduPonz
Copy link
Member

EduPonz commented Feb 22, 2021

Hi @TSC21 ,

I think it'd be good if you could file a different ticket with some steps to reproduce your issue so we can investigate it thoroughly. I'd prefer to have two different tickets since you issue is somehow related to this one, but it seems is not the same as what the OP posted here.

@goekce
Copy link

goekce commented Mar 24, 2021

I also had the same issue on a multi-user machine. Two users on the same machine, i.e., two UIDs cannot communicate with eachother anymore with the new FastDDS version and I have to use @richiware s workaround.

@richiware said that the project is working on this problem, so this issue should be opened again in my opinion.

@MiguelCompany
Copy link
Member

@goekce Your issue is the same as #1750, which has not been closed yet. PR #1801 will fix it, but is not finished yet.

hmakelin added a commit to hmakelin/gisnav-docker that referenced this issue Aug 18, 2022
…ontainer from the host by mapping shared memory (see discussion here: eProsima/Fast-DDS#1698). This is needed e.g. if you want to run GISNav on host while using the containerized SITL environment. Also make ROS_DOMAIN_ID a build argument for the px4-sitl container image and add a short related note to the README.md troubleshooting section.
@Paulvp
Copy link

Paulvp commented Jun 28, 2023

First, thanks for the reporting. We usually work with Docker containers, but not with that kind of combination. We were testing your environment and, as you pointed to, some extra configuration should be added to FastDDS. Only for reminder, to configure Fast-DDS there are two ways of telling a ROS 2 application which XML to use :

  • Placing your XML file in the running directory under the name DEFAULT_FASTRTPS_PROFILES.xml.
  • Setting environment variable FASTRTPS_DEFAULT_PROFILES_FILE to contain the path to your XML file (relative to the working directory).

Before configuring Fast-DDS you need to know this information: the IP of your Windows host (the public IP of your local network) and select two ports to be used by Fast-DDS inside the Docker container (these ports cannot be used by other application in your Windows host).

In my testing environment the public IP of my Windows host is 192.168.1.133, and the ports I selected are 7414 and 7415. Here you have the XML I used to make the communication works. The XML comes with comments explained the purpose of each part of the XML.

<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
    <participant profile_name="ROS2_profile" is_default_profile="true">
        <rtps>
            <builtin>
                <!-- This locator is used to tell remote participants where
                they are able to discover me.
                The participant in the Windows host will try to find me in
                192.168.1.133:7414.
                Only setting mettatraffic unicast locators, we are disabling
                multicast communicatins -->
                <metatrafficUnicastLocatorList>
                    <locator>
                        <udpv4>
                            <address>192.168.1.133</address>
                            <port>7414</port>
                        </udpv4>
                    </locator>
                </metatrafficUnicastLocatorList>
                <!-- This locator is used to find remote participants.
                In this case Fast-DDS will try unicast communications
                with the participant in the Windows host.-->
                <initialPeersList>
                    <locator>
                        <udpv4>
                            <address>192.168.1.133</address>
                        </udpv4>
                    </locator>
                </initialPeersList>
            </builtin>
            <!-- This locator is used to configure where the readers will
            be listeing and to tell remote participants where
            they are able to send user data.
            Docker container particpant's endpoints will be listening 
            in 192.168.1.133:7415. -->
            <defaultUnicastLocatorList>
                <locator>
                    <udpv4>
                        <address>192.168.1.133</address>
                        <port>7415</port>
                    </udpv4>
                </locator>
            </defaultUnicastLocatorList>
        </rtps>
    </participant>
</profiles>

Remember mapping the selected ports when creating the docker container.

 docker run -ti --rm -p 7414:7414/udp -p 7415:7415/udp  DOCKER_IMAGE

I hope this is helpful for you.

@richiware and @anastasiapan : Is there a way now to establish a similar connection between ROS publisher/subscriber running in Linux Docker on Windows host and ROS publisher/subscriber natively running on an Ubuntu system (separate PC in the LAN network) ? Can a similar XML file be created to achieve this ? Also, is it possible to enable this with multicast ?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

8 participants