Go to the documentation of this file.00001 import rospy
00002 from BAL.Handlers.incomingDataHandler import IncomingDataHandler
00003 from BAL.Interfaces.Runnable import Runnable
00004 from threading import Condition
00005
00006 __author__ = 'tom1231'
00007
00008
00009 class IncomingMsgHandler(Runnable):
00010 def __init__(self, devs, output):
00011 self._queue = []
00012 self._lock = Condition()
00013 self._devs = devs
00014 self._output = output
00015 self._close = False
00016
00017 def getMsg(self):
00018 with self._lock:
00019 while len(self._queue) == 0:
00020 self._lock.wait()
00021 if self._close : return None
00022 return self._queue.pop(0)
00023
00024 def close(self):
00025 with self._lock:
00026 self._close = True
00027 self._lock.notifyAll()
00028
00029 def addMsg(self, msg):
00030 with self._lock:
00031 self._queue.append(msg)
00032 self._lock.notifyAll()
00033
00034 def run(self):
00035 while not self._close:
00036 msg = self.getMsg()
00037 if msg is not None:
00038 IncomingDataHandler(msg, self._output, self._devs).run()
00039
00040