Go to the documentation of this file.00001
00002
00003 """ diagnostic_updater for Python.
00004 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
00005 """
00006
00007 import roslib
00008 roslib.load_manifest('diagnostic_updater')
00009 import rospy
00010 import threading
00011 from ._update_functions import *
00012
00013
00014 class HeaderlessTopicDiagnostic(CompositeDiagnosticTask):
00015 """A class to facilitate making diagnostics for a topic using a
00016 FrequencyStatus.
00017
00018 The word "headerless" in the class name refers to the fact that it is
00019 mainly designed for use with messages that do not have a header, and
00020 that cannot therefore be checked using a TimeStampStatus.
00021 """
00022
00023 def __init__(self, name, diag, freq):
00024 """Constructs a HeaderlessTopicDiagnostic.
00025
00026 @param name The name of the topic that is being diagnosed.
00027
00028 @param diag The diagnostic_updater that the CompositeDiagnosticTask
00029 should add itself to.
00030
00031 @param freq The parameters for the FrequencyStatus class that will be
00032 computing statistics.
00033 """
00034 CompositeDiagnosticTask.__init__(self, name + " topic status")
00035 self.diag = diag
00036 self.freq = FrequencyStatus(freq)
00037 self.addTask(self.freq)
00038 self.diag.add(self)
00039
00040 def tick(self):
00041 """Signals that a publication has occurred."""
00042 self.freq.tick()
00043
00044 def clear_window(self):
00045 """Clears the frequency statistics."""
00046 self.freq.clear()
00047
00048
00049 class TopicDiagnostic(HeaderlessTopicDiagnostic):
00050 """A class to facilitate making diagnostics for a topic using a
00051 FrequencyStatus and TimeStampStatus.
00052 """
00053
00054 def __init__(self, name, diag, freq, stamp):
00055 """Constructs a TopicDiagnostic.
00056
00057 @param name The name of the topic that is being diagnosed.
00058
00059 @param diag The diagnostic_updater that the CompositeDiagnosticTask
00060 should add itself to.
00061
00062 @param freq The parameters for the FrequencyStatus class that will be
00063 computing statistics.
00064
00065 @param stamp The parameters for the TimeStampStatus class that will be
00066 computing statistics.
00067 """
00068
00069 HeaderlessTopicDiagnostic.__init__(self, name, diag, freq)
00070 self.stamp = TimeStampStatus(stamp)
00071 self.addTask(self.stamp)
00072
00073 def tick(self, stamp):
00074 """Collects statistics and publishes the message.
00075
00076 @param stamp Timestamp to use for interval computation by the
00077 TimeStampStatus class.
00078 """
00079 self.stamp.tick(stamp)
00080 HeaderlessTopicDiagnostic.tick(self)
00081
00082
00083 class DiagnosedPublisher(TopicDiagnostic):
00084 """A TopicDiagnostic combined with a ros::Publisher.
00085
00086 For a standard ros::Publisher, this class allows the ros::Publisher and
00087 the TopicDiagnostic to be combined for added convenience.
00088 """
00089
00090 def __init__(self, pub, diag, freq, stamp):
00091 """Constructs a DiagnosedPublisher.
00092
00093 @param pub The publisher on which statistics are being collected.
00094
00095 @param diag The diagnostic_updater that the CompositeDiagnosticTask
00096 should add itself to.
00097
00098 @param freq The parameters for the FrequencyStatus class that will be
00099 computing statistics.
00100
00101 @param stamp The parameters for the TimeStampStatus class that will be
00102 computing statistics.
00103 """
00104 TopicDiagnostic.__init__(self, pub.name, diag, freq, stamp)
00105 self.publisher = pub
00106
00107 def publish(self, message):
00108 """Collects statistics and publishes the message.
00109
00110 The timestamp to be used by the TimeStampStatus class will be
00111 extracted from message.header.stamp.
00112 """
00113 self.tick(message.header.stamp)
00114 self.publisher.publish(message)