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

support Mirrored mode networking for wsl2 #879

Closed
wants to merge 2 commits into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 12 additions & 4 deletions webots_ros2_driver/webots_ros2_driver/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ def is_wsl():
return 'microsoft-standard' in uname().release


def get_wsl_ip_address():
def get_wsl_host_ip():
try:
file = open('/etc/resolv.conf', 'r')
except IOError:
Expand Down Expand Up @@ -123,7 +123,7 @@ def container_shared_folder():
return shared_folder_list[1]


def get_host_ip():
def get_router_ip():
try:
output = subprocess.run(['ip', 'route'], check=True, stdout=subprocess.PIPE, universal_newlines=True)
for line in output.stdout.split('\n'):
Expand All @@ -135,19 +135,27 @@ def get_host_ip():
sys.exit('Unable to get host IP address. \'ip route\' could not be executed.')


def get_wsl_ip_address():
# wsl2 net mode
# NAT: if get_router_ip() == get_wsl_host_ip()
# Mirrored: if get_router_ip() != get_wsl_host_ip()
wsl_host_ip = get_wsl_host_ip()
return wsl_host_ip if get_router_ip() == wsl_host_ip else '127.0.0.1'


def controller_protocol():
protocol = 'tcp' if (has_shared_folder() or is_wsl()) else 'ipc'
return protocol


def controller_ip_address():
ip_address = get_host_ip() if has_shared_folder() else get_wsl_ip_address()
ip_address = get_router_ip() if has_shared_folder() else get_wsl_ip_address()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
ip_address = get_router_ip() if has_shared_folder() else get_wsl_ip_address()
ip_address = get_router_ip() if has_shared_folder() else get_wsl_host_ip()

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not sure the purpose of the function controller_ip_address. In mirrored mode, the return value of get_wsl_host_ip is fixed as 127.0.0.42

return ip_address


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 + '/'
return 'tcp://' + (get_router_ip() if has_shared_folder() else get_wsl_ip_address()) + ':' + port + '/'
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
return 'tcp://' + (get_router_ip() if has_shared_folder() else get_wsl_ip_address()) + ':' + port + '/'
return 'tcp://' + (get_router_ip() if has_shared_folder() else get_wsl_host_ip()) + ':' + port + '/'

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

but get_wsl_ip_address shoud be used here

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You renamed this get_wsl_ip_address function to get_wsl_host_ip.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if the file /etc/resolv.conf exist, the function get_wsl_host_ip never return 127.0.0.1 whatever the mode.
But get_wsl_ip_address can return get_wsl_host_ip or localhost

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What I mean here is that in this PR, get_wsl_ip_address doesn't exist any more. You renamed it to get_wsl_host_ip. So, the above line will fail due to an attempt to call an unknown function.

else:
return ''

Expand Down
Loading