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

Compatibility for Docker on macOS #848

Open
wants to merge 11 commits into
base: master
Choose a base branch
from
32 changes: 18 additions & 14 deletions webots_ros2_driver/scripts/webots_tcp_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,29 +41,33 @@ def get_host_ip():
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.')
sys.exit('Unable to get host IP address. \'ip route\' could not be executed. Make sure that iproute2 is installed.')


HOST = get_host_ip() # Connect to host of the VM
PORT = 2000 # Port to connect to
def host_shared_folder():
shared_folder_list = os.environ['WEBOTS_SHARED_FOLDER'].split(':')
return shared_folder_list[0]


simulation_server_ip = None
simulation_server_port = None

tcp_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
launch_arguments = ''
for arg in sys.argv:
if arg.endswith('.py') or arg == '':
continue
elif arg.endswith('.wbt'):
for arg in sys.argv[1:]:
if arg.endswith('.wbt'):
world_name = arg
elif "--simulation_server_ip=" in arg:
simulation_server_ip = arg.replace("--simulation_server_ip=", "")
elif "--simulation_server_port=" in arg:
simulation_server_port = int(arg.replace("--simulation_server_port=", ""))
else:
launch_arguments = launch_arguments + ' ' + arg

simulation_server_ip = get_host_ip() if simulation_server_ip is None else simulation_server_ip
simulation_server_port = 2000 if simulation_server_port is None else simulation_server_port

def host_shared_folder():
shared_folder_list = os.environ['WEBOTS_SHARED_FOLDER'].split(':')
return shared_folder_list[0]


while tcp_socket.connect_ex((HOST, PORT)) != 0:
tcp_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
while tcp_socket.connect_ex((simulation_server_ip, simulation_server_port)) != 0:
print('WARNING: Unable to start Webots. Please start the local simulation server on your host machine. Next connection '
'attempt in 1 second.', file=sys.stderr)
time.sleep(1)
Expand Down
6 changes: 4 additions & 2 deletions webots_ros2_driver/webots_ros2_driver/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ def get_host_ip():
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.')
sys.exit('Unable to get host IP address. \'ip route\' could not be executed. Make sure that iproute2 is installed.')


def controller_protocol():
Expand All @@ -153,7 +153,9 @@ def controller_ip_address():
return ip_address


def controller_url_prefix(port='1234'):
def controller_url_prefix(ip_address=None, port='1234'):
if ip_address is not None:
return 'tcp://' + str(ip_address) + ':' + port + '/'
if has_shared_folder() or is_wsl():
return 'tcp://' + (get_host_ip() if has_shared_folder() else get_wsl_ip_address()) + ':' + port + '/'
else:
Expand Down
6 changes: 3 additions & 3 deletions webots_ros2_driver/webots_ros2_driver/webots_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,11 @@

class WebotsController(ExecuteProcess):
def __init__(self, output='screen', respawn=False, remappings=[],
namespace='', parameters=[], robot_name='', port='1234', **kwargs):
namespace='', parameters=[], robot_name='', ip_address='', webots_port='1234', **kwargs):
webots_controller = (os.path.join(get_package_share_directory('webots_ros2_driver'), 'scripts', 'webots-controller'))

protocol = controller_protocol()
ip_address = controller_ip_address() if (protocol == 'tcp') else ''
ip_address = controller_ip_address() if (ip_address == '' and protocol == 'tcp') else ip_address

robot_name_option = [] if not robot_name else ['--robot-name=' + robot_name]
ip_address_option = [] if not ip_address else ['--ip-address=' + ip_address]
Expand Down Expand Up @@ -67,7 +67,7 @@ def __init__(self, output='screen', respawn=False, remappings=[],
*robot_name_option,
['--protocol=', protocol],
*ip_address_option,
['--port=', port],
['--port=', webots_port],
'ros2',
*ros_args,
*ros_arguments,
Expand Down
19 changes: 12 additions & 7 deletions webots_ros2_driver/webots_ros2_driver/webots_launcher.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ def perform(self, context):

class WebotsLauncher(ExecuteProcess):
def __init__(self, output='screen', world=None, gui=True, mode='realtime', stream=False, ros2_supervisor=False,
port='1234', **kwargs):
webots_port='1234', simulation_server_ip=None, simulation_server_port=2000, **kwargs):
if sys.platform == 'win32':
kalle264 marked this conversation as resolved.
Show resolved Hide resolved
print('WARNING: Native webots_ros2 compatibility with Windows is deprecated and will be removed soon. Please use a '
'WSL (Windows Subsystem for Linux) environment instead.', file=sys.stderr)
Expand All @@ -64,7 +64,7 @@ def __init__(self, output='screen', world=None, gui=True, mode='realtime', strea
self.__has_shared_folder = has_shared_folder()
self.__is_supervisor = ros2_supervisor
if self.__is_supervisor:
self._supervisor = Ros2SupervisorLauncher(port=port)
self._supervisor = Ros2SupervisorLauncher(simulation_server_ip=simulation_server_ip, webots_port=webots_port)

# Find Webots executable
if not self.__has_shared_folder:
Expand Down Expand Up @@ -98,7 +98,10 @@ def __init__(self, output='screen', world=None, gui=True, mode='realtime', strea
stream_argument = _ConditionalSubstitution(condition=stream, true_value='--stream')
else:
stream_argument = "--stream=" + stream
port_argument = '--port=' + port
webots_port_argument = '--port=' + webots_port

simulation_server_ip_argument = "" if simulation_server_ip is None else "--simulation_server_ip=" + simulation_server_ip
simulation_server_port_argument = "" if simulation_server_port is None else "--simulation_server_port=" + str(simulation_server_port)

xvfb_run_prefix = []

Expand All @@ -117,7 +120,9 @@ def __init__(self, output='screen', world=None, gui=True, mode='realtime', strea
'python3',
webots_tcp_client,
stream_argument,
port_argument,
webots_port_argument,
simulation_server_ip_argument,
simulation_server_port_argument,
no_rendering,
stdout,
stderr,
Expand All @@ -137,7 +142,7 @@ def __init__(self, output='screen', world=None, gui=True, mode='realtime', strea
cmd=xvfb_run_prefix + [
webots_path,
stream_argument,
port_argument,
webots_port_argument,
no_rendering,
stdout,
stderr,
Expand Down Expand Up @@ -261,7 +266,7 @@ def _shutdown_process(self, context, *, send_sigint):


class Ros2SupervisorLauncher(Node):
def __init__(self, output='screen', respawn=True, port='1234', **kwargs):
def __init__(self, output='screen', respawn=True, simulation_server_ip=None, webots_port='1234', **kwargs):
# Launch the Ros2Supervisor node
super().__init__(
package='webots_ros2_driver',
Expand All @@ -271,7 +276,7 @@ def __init__(self, output='screen', respawn=True, port='1234', **kwargs):
output=output,
# Set WEBOTS_HOME to the webots_ros2_driver installation folder
# to load the correct libController libraries from the Python API
additional_env={'WEBOTS_CONTROLLER_URL': controller_url_prefix(port) + 'Ros2Supervisor',
additional_env={'WEBOTS_CONTROLLER_URL': controller_url_prefix(ip_address=simulation_server_ip, port=webots_port) + 'Ros2Supervisor',
'WEBOTS_HOME': get_package_prefix('webots_ros2_driver')},
respawn=respawn,
**kwargs
Expand Down
Loading