Skip to content

Commit

Permalink
Merge pull request #117 from gramaziokohler/fix-reconnection-on-ironp…
Browse files Browse the repository at this point in the history
…ython

Fixed reconnection issues on IronPython
  • Loading branch information
gonzalocasas authored Mar 29, 2023
2 parents 8244222 + ce560a3 commit 874a0db
Show file tree
Hide file tree
Showing 4 changed files with 51 additions and 6 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,14 @@ Unreleased

**Added**

* Added a wait event to close on IronPython to ensure the close request is sent before returning.

**Changed**

**Fixed**

* Fixed reconnection behavior on IronPython which would trigger reconnects even after a manual disconnect.

**Deprecated**

**Removed**
Expand Down
11 changes: 6 additions & 5 deletions src/roslibpy/comm/comm_cli.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ def on_open(self, task):
return

LOGGER.info('Connection to ROS ready.')
self._manual_disconnect = False
self.factory.manual_disconnect = False
self.factory.ready(self)
self.factory.manager.call_in_thread(self.start_listening)

Expand Down Expand Up @@ -174,7 +174,7 @@ def start_listening(self):

def send_close(self):
"""Trigger the closure of the websocket indicating normal closing process."""
self._manual_disconnect = True
self.factory.manual_disconnect = True

err_desc = ''
err_code = WebSocketCloseStatus.NormalClosure
Expand Down Expand Up @@ -273,6 +273,7 @@ class CliRosBridgeClientFactory(EventEmitterMixin):
def __init__(self, url, *args, **kwargs):
super(CliRosBridgeClientFactory, self).__init__(*args, **kwargs)
self._manager = CliEventLoopManager()
self.manual_disconnect = False
self.proto = None
self.url = url
self.delay = self.initial_delay
Expand Down Expand Up @@ -313,16 +314,16 @@ def reset_delay(self):
self.delay = self.initial_delay

def _reconnect_if_needed(self):
if self.proto and self.proto._manual_disconnect:
if self.manual_disconnect:
return

if self.max_retries is not None and (self.retries >= self.max_retries):
LOGGER.info('Abandonning after {} retries'.format(self.retries))
LOGGER.info("Abandoning after {} retries".format(self.retries))
return

self.retries += 1
self.delay = min(self.delay * self.factor, self.max_delay)
LOGGER.info('Connection manager will retry in {} seconds'.format(int(self.delay)))
LOGGER.info("Connection manager will retry in {} seconds".format(int(self.delay)))

self.manager.call_later(self.delay, self.connect)

Expand Down
7 changes: 6 additions & 1 deletion src/roslibpy/ros.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,17 +74,22 @@ def _unset_connecting_flag(*args):
self.factory.on_ready(_unset_connecting_flag)
self.factory.connect()

def close(self):
def close(self, timeout=CONNECTION_TIMEOUT):
"""Disconnect from ROS."""
if self.is_connected:
wait_disconnect = threading.Event()

def _wrapper_callback(proto):
self.emit("closing")
proto.send_close()
wait_disconnect.set()
return proto

self.factory.on_ready(_wrapper_callback)

if not wait_disconnect.wait(timeout):
raise RosTimeoutError("Failed to disconnect to ROS")

def run(self, timeout=CONNECTION_TIMEOUT):
"""Kick-starts a non-blocking event loop.
Expand Down
35 changes: 35 additions & 0 deletions tests/test_ros.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,3 +58,38 @@ def handle_closing():
assert ctx["closing_event_called"]
assert ctx["was_still_connected"]
assert closing_was_handled_synchronously_before_close


def test_multithreaded_connect_disconnect():
CONNECTIONS = 30
clients = []

def connect(clients):
ros = Ros(url)
ros.run()
clients.append(ros)

# First connect all
threads = []
for _ in range(CONNECTIONS):
thread = threading.Thread(target=connect, args=(clients,))
thread.daemon = False
thread.start()
threads.append(thread)

for thread in threads:
thread.join()

# Assert connection status
for ros in clients:
assert ros.is_connected

# Now disconnect all
for ros in clients:
ros.close()

time.sleep(0.5)

# Assert connection status
for ros in clients:
assert not ros.is_connected

0 comments on commit 874a0db

Please sign in to comment.