topicOccurances.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 ##
00004 # observers_generator.py is a node that finds the nodes and topics and their related information in the running system.
00005 # After finding necessary information it creates launch files in tug_ist_diagnosis_launch package and executes them automatically. 
00006 # Copyright (c).2012. OWNER: Institute for Software Technology, TU Graz Austria.
00007 # Authors: Safdar Zaman, Gerald Steinbauer. (szaman@ist.tugraz.at, steinbauer@ist.tugraz.at)
00008 # All rights reserved.
00009 #    This program is free software: you can redistribute it and/or modify
00010 #    it under the terms of the GNU General Public License as published by
00011 #    the Free Software Foundation, either version 3 of the License, or
00012 #    (at your option) any later version.
00013 #
00014 #    This program is distributed in the hope that it will be useful,
00015 #    but WITHOUT ANY WARRANTY; without even the implied warranty of
00016 #    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00017 #    GNU General Public License for more details.
00018 #
00019 #    You should have received a copy of the GNU General Public License
00020 #    along with this program.  If not, see <http://www.gnu.org/licenses/>.
00021 ##
00022 
00023 import roslib.message;roslib.load_manifest('tug_ist_diagnosis_generator')
00024 import rospy
00025 import sys
00026 import xmlrpclib
00027 import os
00028 import subprocess
00029 import time
00030 import shlex
00031 import thread
00032 from math import sqrt
00033 import time
00034 class Generator(object):
00035         def __init__(self):
00036                 rospy.init_node('observers_generator', anonymous=False)
00037                 self.m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00038                 self.caller_id = '/script'
00039                 self.mapping = []
00040                 self.dataMAT = [[]]
00041                 self.dataFile = open('safdarFile', 'w')
00042                 
00043         def start(self):
00044                 self.extract_nodes_topics()
00045 
00046         def end(self):
00047                 self.dataFile.close()
00048 
00049         def callback(self,data,topic):
00050                 curr_t = time.time()
00051                 self.dataFile.write(str(curr_t)+'\n')
00052                 rospy.loginfo('type = '+str(data.header))
00053                 
00054 
00055         def extract_nodes_topics(self):
00056                 pubcode, statusMessage, topicList = self.m.getPublishedTopics(self.caller_id, "")
00057                 for topic in topicList:
00058                         if (topic[0] == '/rosout') | (topic[0] == '/rosout_agg'):
00059                                 continue
00060                         #self.mapping[9] = topic[1]
00061                         print topic[1]
00062                         msg_class = roslib.message.get_message_class(topic[1])
00063                         rospy.Subscriber(topic[0], msg_class, self.callback, topic[0])
00064                 rospy.spin()            
00065         
00066 if __name__ == '__main__':
00067       generator = Generator()
00068       generator.start()
00069       generator.end()


tug_ist_diagnosis_generator
Author(s): Safdar Zaman, Gerald Steinbauer
autogenerated on Mon Jan 6 2014 11:51:14