Go to the documentation of this file.00001 import roslib; roslib.load_manifest('webui')
00002 import rospy
00003 import sys
00004 import rosweb
00005 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00006
00007
00008 class Status(rosweb.ROSWebSubTopic):
00009 def __init__(self, topic, factory, main_rwt):
00010 rosweb.ROSWebSubTopic.__init__(self, topic, factory, main_rwt)
00011
00012 def transform(self, msg):
00013 statuses = msg.status
00014 for status in statuses:
00015 if not status.name.startswith('/'):
00016 status.name = '/' + status.name
00017
00018 def top_only(status): return status.name.count("/") < 2
00019 filtered_statuses = filter(top_only, statuses)
00020 levels = [status.level for status in filtered_statuses]
00021
00022 new_message = DiagnosticStatus()
00023 new_message.name = "Robot Status"
00024 new_message.level = max(levels)
00025
00026 return new_message
00027
00028 class Summary(rosweb.ROSWebSubTopic):
00029 def __init__(self, topic, factory, main_rwt):
00030 rosweb.ROSWebSubTopic.__init__(self, topic, factory, main_rwt)
00031
00032 def transform(self, msg):
00033 statuses = msg.status
00034 for status in statuses:
00035 if not status.name.startswith('/'):
00036 status.name = '/' + status.name
00037
00038 def top_only(status): return status.name.count("/") < 2
00039 filtered_statuses = filter(top_only, statuses)
00040
00041
00042
00043
00044
00045
00046 new_message = DiagnosticArray()
00047 new_message.status = filtered_statuses
00048
00049 return new_message
00050
00051 class FilterDevice(rosweb.ROSWebSubTopic):
00052 def __init__(self, topic, factory, main_rwt):
00053 rosweb.ROSWebSubTopic.__init__(self, topic, factory, main_rwt)
00054 _, _, self.params = rosweb.splitTopic(topic)
00055
00056 def transform(self, msg):
00057 subtopic = self.params
00058 statuses = msg.status
00059 for status in statuses:
00060 if not status.name.startswith('/'):
00061 status.name = '/' + status.name
00062
00063 def device(status): return status.name.startswith(subtopic)
00064 filtered_statuses = filter(device, statuses)
00065
00066 new_message = DiagnosticArray()
00067 new_message.status = filtered_statuses
00068
00069 return new_message
00070
00071 def config_plugin(context):
00072 context.register_subtopic("/diagnostics_agg:filter", FilterDevice)
00073 context.register_subtopic("/diagnostics_agg:Summary", Summary)
00074 context.register_subtopic("/diagnostics_agg:Status", Status)