Go to the documentation of this file.00001
00002
00003 import subprocess
00004 import threading
00005 import time
00006
00007 import roslib
00008 from roslib import scriptutil
00009
00010 class Topics(roslib.message.Message):
00011 __slots__ = ('pubtopics', 'subtopics','nodes')
00012 def __init__(self, topics):
00013 self.pubtopics, self.subtopics, self.nodes = topics
00014
00015 def succeed(args):
00016 code, msg, val = args
00017 if code != 1:
00018 raise RosTopicException("remote call failed: %s"%msg)
00019 return val
00020
00021
00022 class TopicThread(threading.Thread):
00023 def __init__(self):
00024 threading.Thread.__init__(self)
00025
00026 self.callback = None
00027
00028 def setCallback(self, callback):
00029 self.callback = callback
00030
00031 def getTopics(self):
00032 def topic_type(t, pub_topics):
00033 matches = [t_type for t_name, t_type in pub_topics if t_name == t]
00034 if matches:
00035 return matches[0]
00036 return 'unknown type'
00037
00038 master = scriptutil.get_master()
00039 topic = None
00040
00041 state = succeed(master.getSystemState('/rostopic'))
00042 pubs, subs, _ = state
00043
00044 pub_topics = succeed(scriptutil.get_master().getPublishedTopics('/rostopic', '/'))
00045 pubtopics = [t for t,_ in pubs]
00046 pubtopics.sort()
00047
00048 subtopics = [t for t,_ in subs]
00049 subtopics.sort()
00050
00051 nodes = []
00052
00053 for s in state:
00054 for t, l in s:
00055 nodes.extend(l)
00056
00057 nodes = set(nodes)
00058 nodes = list(nodes)
00059 nodes.sort()
00060
00061 topics = (tuple(pubtopics), tuple(subtopics), tuple(nodes))
00062
00063 return topics
00064
00065 def run(self):
00066 lasttopics = ()
00067 while 1:
00068 try:
00069 topics = self.getTopics()
00070 if topics != lasttopics:
00071 lasttopics = topics
00072 self.callback(Topics(topics))
00073 except:
00074 pass
00075 time.sleep(3)
00076
00077