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 import roslib.message; roslib.load_manifest('tug_ist_diagnosis_observers')
00024 import rospy
00025 import sys
00026 import xmlrpclib
00027 import os
00028 from tug_ist_diagnosis_msgs.msg import Observations
00029 import thread
00030 import time
00031
00032 class Diagnostic_Observer(object):
00033
00034 def __init__(self, top):
00035 rospy.init_node('DObs', anonymous=True)
00036 self.caller_id = '/script'
00037 self.m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00038 self.top = top
00039 self.topic = ""
00040 self.topic_type = ""
00041 self.pub = rospy.Publisher('/observations', Observations)
00042 self.param_dev_node = rospy.get_param('~node', 'hokuyo_node')
00043 thread.start_new_thread(self.check_topic,(self.top,2))
00044
00045 def start(self):
00046 pubcode, statusMessage, topicList = self.m.getPublishedTopics(self.caller_id, "")
00047 top_found = False
00048 for item in topicList:
00049 if item[0] == self.top:
00050 self.topic = item[0]
00051 self.topic_type = item[1]
00052 top_found = True
00053 if top_found == True:
00054 msg_class = roslib.message.get_message_class(self.topic_type)
00055 else:
00056 self.report_error()
00057 rospy.Subscriber(self.topic, msg_class, self.access_data)
00058 rospy.spin()
00059
00060 def access_data(self,data):
00061 temp_data = data
00062 for f in temp_data.__slots__:
00063 if f == "status":
00064 a = getattr(temp_data, f)
00065 i=0
00066 print "\n"
00067 while (i<len(a)):
00068 obs_msg = []
00069 if self.param_dev_node in a[i].name :
00070 print a[i].name
00071 if a[i].level == 0:
00072 print "Name:",a[i].name, "OK"
00073 obs_msg.append('ok('+self.param_dev_node+')')
00074 self.pub.publish(Observations(time.time(),obs_msg))
00075 elif a[i].level == 1:
00076 print "Name:",a[i].name, "WARNINNG"
00077 obs_msg.append('ok('+self.param_dev_node+')')
00078 self.pub.publish(Observations(time.time(),obs_msg))
00079 else:
00080 print "Name:",a[i].name, "ERROR"
00081 obs_msg.append('n_ok('+self.param_dev_node+')')
00082 self.pub.publish(Observations(time.time(),obs_msg))
00083 else:
00084 print a[i].name
00085 print self.param_dev_node + " not found."
00086 i = i+1
00087
00088 def check_topic(self,top,sleeptime,*args):
00089 while True:
00090 t = 0
00091 m = xmlrpclib.ServerProxy(os.environ['ROS_MASTER_URI'])
00092 pubcode, statusMessage, topicList = m.getPublishedTopics(self.caller_id, "")
00093 for item in topicList:
00094 if item[0] == top:
00095 self.Topic = True
00096 t = 1
00097 break
00098 if t == 0:
00099 t = 1
00100 print "Topic:[" +top+ "] does not exist."
00101 self.pub.publish(Observations(time.time(),['~ok('+self.param_dev_node+')']))
00102 time.sleep(sleeptime)
00103
00104
00105 def report_error(self):
00106 print 'rosrun tug_ist_diagnosis_observers DObs.py <device_node_name>'
00107 print 'e.g rosrun tug_ist_diagnosis_observers DObs.py _dev_node:=hokuyo_node'
00108 sys.exit(os.EX_USAGE)
00109
00110
00111 if __name__ == '__main__':
00112 dobs = Diagnostic_Observer("/diagnostics")
00113 dobs.start()