Skip to content

Commit 5f13bb3

Browse files
Fix AttributeError isAlive (#2092)
* fix: roscore -> AttributeError: 'ProcessMonitor' object has no attribute 'isAlive' * Fix AttributeError: 'Thread' object has no attribute 'isAlive' * Update remaining instances of isAlive to is_alive Keep mock method isAlive to keep backwards compatibility for users who happen to be using the mock object. Signed-off-by: Jacob Perron <jacob@openrobotics.org> Co-authored-by: Jacob Perron <jacob@openrobotics.org>
1 parent 30d8e9d commit 5f13bb3

File tree

3 files changed

+14
-9
lines changed

3 files changed

+14
-9
lines changed

clients/rospy/src/rospy/core.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -509,7 +509,7 @@ def _add_shutdown_thread(t):
509509
# last thread may not get reaped until shutdown, but this is
510510
# relatively minor
511511
for other in _shutdown_threads[:]:
512-
if not other.isAlive():
512+
if not other.is_alive():
513513
_shutdown_threads.remove(other)
514514
_shutdown_threads.append(t)
515515

@@ -595,7 +595,7 @@ def signal_shutdown(reason):
595595
threads = _shutdown_threads[:]
596596

597597
for t in threads:
598-
if t.isAlive():
598+
if t.is_alive():
599599
t.join(_TIMEOUT_SHUTDOWN_JOIN)
600600
del _shutdown_threads[:]
601601
try:

tools/roslaunch/src/roslaunch/pmon.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ def shutdown_process_monitor(process_monitor):
113113
process_monitor.shutdown()
114114
#logger.debug("shutdown_process_monitor: joining ProcessMonitor")
115115
process_monitor.join(20.0)
116-
if process_monitor.isAlive():
116+
if process_monitor.is_alive():
117117
logger.error("shutdown_process_monitor: ProcessMonitor shutdown failed!")
118118
return False
119119
else:

tools/roslaunch/test/unit/test_roslaunch_pmon.py

+11-6
Original file line numberDiff line numberDiff line change
@@ -54,9 +54,14 @@ def __init__(self):
5454
self.alive = False
5555
self.is_shutdown = False
5656

57+
# The preferred method is 'is_alive'
58+
# Keep this method around for backwards compatibility
5759
def isAlive(self):
5860
return self.alive
5961

62+
def is_alive(self):
63+
return self.alive
64+
6065
def join(self, *args):
6166
return
6267

@@ -302,9 +307,9 @@ def failer():
302307

303308
# Test with a real process monitor
304309
pmon = roslaunch.pmon.start_process_monitor()
305-
self.assert_(pmon.isAlive())
310+
self.assert_(pmon.is_alive())
306311
self.assert_(roslaunch.pmon.shutdown_process_monitor(pmon))
307-
self.failIf(pmon.isAlive())
312+
self.failIf(pmon.is_alive())
308313

309314
# fiddle around with some state that would shouldn't be
310315
roslaunch.pmon._shutting_down = True
@@ -321,13 +326,13 @@ def test_pmon_shutdown(self):
321326
# pmon_shutdown
322327
pmon1 = roslaunch.pmon.start_process_monitor()
323328
pmon2 = roslaunch.pmon.start_process_monitor()
324-
self.assert_(pmon1.isAlive())
325-
self.assert_(pmon2.isAlive())
329+
self.assert_(pmon1.is_alive())
330+
self.assert_(pmon2.is_alive())
326331

327332
roslaunch.pmon.pmon_shutdown()
328333

329-
self.failIf(pmon1.isAlive())
330-
self.failIf(pmon2.isAlive())
334+
self.failIf(pmon1.is_alive())
335+
self.failIf(pmon2.is_alive())
331336

332337
def test_add_process_listener(self):
333338
# coverage test, not a functionality test as that would be much more difficult to simulate

0 commit comments

Comments
 (0)