Skip to content

Commit 874a0db

Browse files
authored
Merge pull request #117 from gramaziokohler/fix-reconnection-on-ironpython
Fixed reconnection issues on IronPython
2 parents 8244222 + ce560a3 commit 874a0db

File tree

4 files changed

+51
-6
lines changed

4 files changed

+51
-6
lines changed

CHANGELOG.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,14 @@ Unreleased
1212

1313
**Added**
1414

15+
* Added a wait event to close on IronPython to ensure the close request is sent before returning.
16+
1517
**Changed**
1618

1719
**Fixed**
1820

21+
* Fixed reconnection behavior on IronPython which would trigger reconnects even after a manual disconnect.
22+
1923
**Deprecated**
2024

2125
**Removed**

src/roslibpy/comm/comm_cli.py

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ def on_open(self, task):
7070
return
7171

7272
LOGGER.info('Connection to ROS ready.')
73-
self._manual_disconnect = False
73+
self.factory.manual_disconnect = False
7474
self.factory.ready(self)
7575
self.factory.manager.call_in_thread(self.start_listening)
7676

@@ -174,7 +174,7 @@ def start_listening(self):
174174

175175
def send_close(self):
176176
"""Trigger the closure of the websocket indicating normal closing process."""
177-
self._manual_disconnect = True
177+
self.factory.manual_disconnect = True
178178

179179
err_desc = ''
180180
err_code = WebSocketCloseStatus.NormalClosure
@@ -273,6 +273,7 @@ class CliRosBridgeClientFactory(EventEmitterMixin):
273273
def __init__(self, url, *args, **kwargs):
274274
super(CliRosBridgeClientFactory, self).__init__(*args, **kwargs)
275275
self._manager = CliEventLoopManager()
276+
self.manual_disconnect = False
276277
self.proto = None
277278
self.url = url
278279
self.delay = self.initial_delay
@@ -313,16 +314,16 @@ def reset_delay(self):
313314
self.delay = self.initial_delay
314315

315316
def _reconnect_if_needed(self):
316-
if self.proto and self.proto._manual_disconnect:
317+
if self.manual_disconnect:
317318
return
318319

319320
if self.max_retries is not None and (self.retries >= self.max_retries):
320-
LOGGER.info('Abandonning after {} retries'.format(self.retries))
321+
LOGGER.info("Abandoning after {} retries".format(self.retries))
321322
return
322323

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

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

src/roslibpy/ros.py

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,17 +74,22 @@ def _unset_connecting_flag(*args):
7474
self.factory.on_ready(_unset_connecting_flag)
7575
self.factory.connect()
7676

77-
def close(self):
77+
def close(self, timeout=CONNECTION_TIMEOUT):
7878
"""Disconnect from ROS."""
7979
if self.is_connected:
80+
wait_disconnect = threading.Event()
8081

8182
def _wrapper_callback(proto):
8283
self.emit("closing")
8384
proto.send_close()
85+
wait_disconnect.set()
8486
return proto
8587

8688
self.factory.on_ready(_wrapper_callback)
8789

90+
if not wait_disconnect.wait(timeout):
91+
raise RosTimeoutError("Failed to disconnect to ROS")
92+
8893
def run(self, timeout=CONNECTION_TIMEOUT):
8994
"""Kick-starts a non-blocking event loop.
9095

tests/test_ros.py

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,3 +58,38 @@ def handle_closing():
5858
assert ctx["closing_event_called"]
5959
assert ctx["was_still_connected"]
6060
assert closing_was_handled_synchronously_before_close
61+
62+
63+
def test_multithreaded_connect_disconnect():
64+
CONNECTIONS = 30
65+
clients = []
66+
67+
def connect(clients):
68+
ros = Ros(url)
69+
ros.run()
70+
clients.append(ros)
71+
72+
# First connect all
73+
threads = []
74+
for _ in range(CONNECTIONS):
75+
thread = threading.Thread(target=connect, args=(clients,))
76+
thread.daemon = False
77+
thread.start()
78+
threads.append(thread)
79+
80+
for thread in threads:
81+
thread.join()
82+
83+
# Assert connection status
84+
for ros in clients:
85+
assert ros.is_connected
86+
87+
# Now disconnect all
88+
for ros in clients:
89+
ros.close()
90+
91+
time.sleep(0.5)
92+
93+
# Assert connection status
94+
for ros in clients:
95+
assert not ros.is_connected

0 commit comments

Comments
 (0)