Skip to content

Commit

Permalink
GraphListener periodically checks if rclpy is shutdown
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Oct 24, 2017
1 parent d8521cd commit d10ee26
Showing 1 changed file with 20 additions and 9 deletions.
29 changes: 20 additions & 9 deletions rclpy/rclpy/graph_listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,11 @@
import threading
import traceback

from rclpy.constants import S_TO_NS
from rclpy.impl.implementation_singleton import rclpy_implementation as _rclpy
import rclpy.logging
from rclpy.timer import WallTimer as _WallTimer
from rclpy.utilities import ok as _ok
from rclpy.wait_set import WaitSet as _WaitSet


Expand All @@ -41,12 +43,16 @@ def __init__(self):
self._wait_set.add_guard_condition(self._gc_handle, self._gc_pointer)

def __del__(self):
with self._lock:
th = self._thread
self._thread = None
if th:
th.join()
_rclpy.rclpy_destroy_entity('guard_condition', self._gc_handle)
self.destroy()

@classmethod
def destroy(cls):
self = getattr(cls, '__singleton')
if self is not None:
with self._lock:
setattr(cls, '__singleton', None)
self._thread = None
_rclpy.rclpy_destroy_entity('guard_condition', self._gc_handle)

def _try_start_thread(self):
# Assumes lock is already held
Expand Down Expand Up @@ -134,11 +140,16 @@ def remove_callback(self, node_handle, callback):

def _runner(self):
while True:
# Wait forever
self._wait_set.wait(-1)
# Wait 1 second
self._wait_set.wait(S_TO_NS)

# notify graph event subscribers
with self._lock:
# Shutdown if necessary
if not _ok():
self.destroy()
break

# notify graph event subscribers
if not self._thread:
# Asked to shut down thread
return
Expand Down

0 comments on commit d10ee26

Please sign in to comment.