Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027 import roslib.message; roslib.load_manifest('tug_ist_diagnosis_observers')
00028 import rospy
00029 import sys
00030 import xmlrpclib
00031 import os
00032 from tug_ist_diagnosis_msgs.msg import Observations
00033 import thread
00034 import time
00035 import traceback
00036
00037 class Hardware_Observer(object):
00038
00039 def __init__(self):
00040 rospy.init_node('HObs', anonymous=True)
00041 self.caller_id = '/script'
00042 self.m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00043 self.topic = ""
00044 self.topic_type = ""
00045 self.pub = rospy.Publisher('/observations', Observations)
00046 self.top = rospy.get_param('~topic', '/board_measurments')
00047 thread.start_new_thread(self.check_topic,(self.top,2))
00048
00049 def start(self):
00050 pubcode, statusMessage, topicList = self.m.getPublishedTopics(self.caller_id, "")
00051 top_found = False
00052 for item in topicList:
00053 if item[0] == self.top:
00054 self.topic = item[0]
00055 self.topic_type = item[1]
00056 top_found = True
00057 if top_found == True:
00058 msg_class = roslib.message.get_message_class(self.topic_type)
00059 else:
00060 self.report_error()
00061 print "HObs is up...."
00062 rospy.Subscriber(self.topic, msg_class, self.access_data)
00063 rospy.spin()
00064
00065 def access_data(self,data):
00066 temp_data = data
00067 for f in temp_data.__slots__:
00068 if f == "channel":
00069 att = getattr(temp_data, f)
00070 j=0
00071 obs_msg = []
00072 while (j<len(att)):
00073 if att[j].status == 1:
00074 obs_msg.append('on('+att[j].dev_connected+')')
00075 else:
00076 obs_msg.append('~on('+att[j].dev_connected+')')
00077 j = j + 1
00078 self.pub.publish(Observations(time.time(),obs_msg))
00079
00080
00081 def check_topic(self,top,sleeptime,*args):
00082 try:
00083 while True:
00084 t = 0
00085 m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00086 pubcode, statusMessage, topicList = m.getPublishedTopics(self.caller_id, "")
00087 for item in topicList:
00088 if item[0] == top:
00089 self.Topic = True
00090 t = 1
00091 break
00092 if t == 0:
00093 t = 1
00094 print "Topic:[" +top+ "] does not exist."
00095 time.sleep(sleeptime)
00096 except:
00097 print "An unhandled exception occured, here's the traceback!"
00098 traceback.print_exc()
00099
00100
00101
00102
00103 def report_error(self):
00104 print 'Incorrect Command:'
00105 print 'use [rosrun tug_ist_diagnosis_observers HObs.py]'
00106 sys.exit(os.EX_USAGE)
00107
00108 def throws():
00109 raise RuntimeError('this is the error message')
00110
00111 if __name__ == '__main__':
00112 hObs = Hardware_Observer()
00113 hObs.start()