Skip to content

Webots Ros2 program (any of the demos) running in Ubuntu (Windows WSL2) is not able to connect to Webots host simulator in Windows 11. #1031

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

Open
andrespineda opened this issue Feb 16, 2025 · 4 comments

Comments

@andrespineda
Copy link

Describe the Bug
After installing Webots on a Windows 11 host configured with a Ubuntu 22.04 on WSL2, any of the demo programs fail in trying to connect to the Windows Webot simulator.

Steps to Reproduce

  1. Install the Ros2 and Webots code as specified in the Ros2 documentation: https://docs.ros.org/en/foxy/Tutorials/Advanced/Simulators/Webots/Installation-Windows.html#install-wsl2https://docs.ros.org/en/foxy/Tutorials/Advanced/Simulators/Webots/Installation-Windows.html#install-wsl2.
  2. After installation, attempt to run the provided demo script: ros2 launch webots_ros2_universal_robot multirobot_launch.py.

Expected behavior
The expectation is that the code will start to run and pop open the Webots simulator window on the Windows host. It will them start to send commands to the robot running in the simulation to perform the demo actions.
Instead, the program starts up, but is unable to connect to the host. The screen continuously displays an error that it cannot connect and will try in a few seconds. It never is able to connect.

Affected Packages
List of affected packages:
All of the demo programs, such as epuck, universal_robot, etc.

Screenshots
Not available

System

  • Webots Version: [R2025a ]
  • ROS Version: [Jazzy]
  • Operating System: [Windows 11, WSL2 Ubuntu 24.04.2 LTS]
  • Graphics Card: [Unknown]

Additional context

I spent over a full day trying to figure this out and found a solution.

In my case, the issue was that the program located in "webots_ros2_driver/lib/python3.12/site-packages/webots-driver/utils.py" has a function named "get_wsl_ip_address()" . This function gets the "nameserver" ip address from the WSL2 "/etc/resolv.conf" file and returns it incorrectly as the ip address of the Windows host. Because of this, the Ubuntu webots controller keeps trying to connect to the webots simulator running on the Windows side using the nameserver ip address as the TCP IP address. I my system, the nameserver was set to 127.0.0.53. The "webots-controller" kept trying to connect to TCP 127.0.0.53 port 1234.

To prove that this was the problem, I manually edited the "/etc/resolv.conf" file and changed the nameserver address to "127.0.0.1".

This worked: I was then able to run "ros2 launch webots_ros2_epuck robot_launch.py"" and it connected up to the webot simulator using TCP 127.0.0.1 Port 1234. Of course this only works while the terminal is open. Once I close the terminal and open it again, the /etc/resolv changes and it starts to fail again.

Changing the nameserver address is not the correct way to fix the problem, but it got me to a working demo and can move on.

I consider the code in utils.py to be an error as the nameserver ip address is not the correct value to use to connect to the Windows host webot simulator.

@pantagnun
Copy link

Hi, pardon. I meet the same problem.I have tried the "Execute_Process" to choose the right windows ip I needed for webots_controller connection and it worked, but the problem occured then. It throwed the exception like below:
[webots-controller-2] terminate called after throwing an instance of 'std::runtime_error'
[webots-controller-2] what(): Error: The Python module with the WebotsNode class cannot be executed.
[webots-controller-2] [ros2run]: Aborted
Have you met the problem too? could you tell me how to fix it? please thx

@Rami-Sabbagh
Copy link
Member

Hello, I was having the same problem. After hours of debugging, I think I have figured out the source of the issue.

WSL is configured by default to use a NAT architecture for the communication between Windows and WSL.

The official Microsoft Documentation on WSL Networking explains how the WSL system its own IP address under a sub-network has, and that windows can connect to any WSL program on localhost normally. But for a WSL program to connect to a Windows one it has to use the proper IP under the WSL sub-network.

The window machine is configured as the gateway within this sub-network, we can lookup it's IP by running ip route within WSL:

$ ip route
default via 172.30.32.1 dev eth0 proto kernel
172.30.32.0/20 dev eth0 proto kernel scope link src 172.30.43.162

It's the one in the first line: 172.30.32.1.

The webots_ros2 package works in WSL by running Webots on Windows like any normal Windows program and connecting to it using TCP. In order to connect it has to use the IP mentioned earlier, 172.30.32.1.

The package has the logic of determining the IP in .../webots_ros2_driver/utils.py. It handles other types of systems too like Docker and macOS. But we're only interested in WSL here.

In the following 2 functions:

def controller_ip_address():
ip_address = get_host_ip() if has_shared_folder() else get_wsl_ip_address()
return ip_address
and
def controller_url_prefix(port='1234'):
if has_shared_folder() or is_wsl():
return 'tcp://' + (get_host_ip() if has_shared_folder() else get_wsl_ip_address()) + ':' + port + '/'
else:
return ''
, we can see how the IP is determined:

get_host_ip() if has_shared_folder() else get_wsl_ip_address()

has_shared_folder() is True when there's a environment variable with the name WEBOTS_SHARED_FOLDER defined, which is not the case with the WSL setup.

def has_shared_folder():
return 'WEBOTS_SHARED_FOLDER' in os.environ

This leaves us with get_wsl_ip_address():

def get_wsl_ip_address():
try:
file = open('/etc/resolv.conf', 'r')
except IOError:
# /etc/resolv.conf doesn't exist, can't be read, etc.
# Use the default resolver configuration.
return '127.0.0.1'
try:
for line in file:
if len(line) == 0 or line[0] == '#' or line[0] == ';':
continue
tokens = line.split()
if len(tokens) == 0:
continue
if tokens[0] == 'nameserver':
file.close()
if len(tokens[1]) == 0:
return '127.0.0.1'
return tokens[1]
finally:
file.close()

It uses the IP address specified in /etc/resolv.conf for connecting to the Windows Webots instance.

Upon checking the file I have found the following:

# This file was automatically generated by WSL. To stop automatic generation of this file, add the following entry to /etc/wsl.conf:
# [network]
# generateResolvConf = false
nameserver 10.255.255.254

10.255.255.254 is not the gateway IP! By checking ip addr we can find out that it is actually a loopback address (similar to 127.0.0.1):

$ ip addr
1: lo: <LOOPBACK,UP,LOWER_UP> mtu 65536 qdisc noqueue state UNKNOWN group default qlen 1000
    link/loopback 00:00:00:00:00:00 brd 00:00:00:00:00:00
    inet 127.0.0.1/8 scope host lo
       valid_lft forever preferred_lft forever
    inet 10.255.255.254/32 brd 10.255.255.254 scope global lo
       valid_lft forever preferred_lft forever
    inet6 ::1/128 scope host
       valid_lft forever preferred_lft forever
2: eth0: <BROADCAST,MULTICAST,UP,LOWER_UP> mtu 1500 qdisc mq state UP group default qlen 1000
    link/ether 00:15:5d:62:37:e2 brd ff:ff:ff:ff:ff:ff
    inet 172.30.43.162/20 brd 172.30.47.255 scope global eth0
       valid_lft forever preferred_lft forever
    inet6 fe80::215:5dff:fe62:37e2/64 scope link
       valid_lft forever preferred_lft forever

Why? WSL has a DNS server running with in itself?

Well, it's a new feature called "DNS Tunneling", and as mentioned in microsoft/WSL#12101 (comment), WSL dnsTunneling it became enabled by default.

So, using the IP address in resolv.conf is not a reliable method for WSL...

Actually the get_host_ip() method would have done the job as it uses ip route:

def get_host_ip():
if is_docker():
return "host.docker.internal"
try:
output = subprocess.run(['ip', 'route'], check=True, stdout=subprocess.PIPE, universal_newlines=True)
for line in output.stdout.split('\n'):
fields = line.split()
if fields and fields[0] == 'default':
return fields[2]
sys.exit('Unable to get host IP address.')
except subprocess.CalledProcessError:
sys.exit('Unable to get host IP address. \'ip route\' could not be executed.')

A quick hackish solution to validate the hypothesis is to modify resolv.conf and set the namespace to the gateway IP:

# This file was automatically generated by WSL. To stop automatic generation of this file, add the following entry to /etc/wsl.conf:
# [network]
# generateResolvConf = false
#nameserver 10.255.255.254
namespace 172.30.32.1

Launching the webots_ros2 example now should work fine, temporarly.

Once WSL is restarted the resolv.conf file is going to be regenerated, overwriting the changes done. Or if configuration file was reloaded, DNS resolving might break in WSL.

@Rami-Sabbagh
Copy link
Member

Disabling the "DNS Tunneling" feature and restarting WSL solves the issue. But we lose the feature.
I think it can be detected by code by a hardcoded check for the IP extracted from resolv.conf, if it's 10.255.255.254 then the feature is active.

When it's active and NAT networking is used, ip route gives the right result.

This leaves the mirrored networking mode to solve.

@myudak
Copy link

myudak commented Apr 24, 2025

is there any simpler solutions? i have the exact same issue

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

No branches or pull requests

4 participants