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
00028
00029
00030
00031
00032
00033
00034
00035 """ diagnostic_updater for Python.
00036 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
00037 """
00038
00039 import roslib
00040 roslib.load_manifest('diagnostic_updater')
00041 import rospy
00042 import threading
00043 from ._update_functions import *
00044
00045
00046 class HeaderlessTopicDiagnostic(CompositeDiagnosticTask):
00047 """A class to facilitate making diagnostics for a topic using a
00048 FrequencyStatus.
00049
00050 The word "headerless" in the class name refers to the fact that it is
00051 mainly designed for use with messages that do not have a header, and
00052 that cannot therefore be checked using a TimeStampStatus.
00053 """
00054
00055 def __init__(self, name, diag, freq):
00056 """Constructs a HeaderlessTopicDiagnostic.
00057
00058 @param name The name of the topic that is being diagnosed.
00059
00060 @param diag The diagnostic_updater that the CompositeDiagnosticTask
00061 should add itself to.
00062
00063 @param freq The parameters for the FrequencyStatus class that will be
00064 computing statistics.
00065 """
00066 CompositeDiagnosticTask.__init__(self, name + " topic status")
00067 self.diag = diag
00068 self.freq = FrequencyStatus(freq)
00069 self.addTask(self.freq)
00070 self.diag.add(self)
00071
00072 def tick(self):
00073 """Signals that a publication has occurred."""
00074 self.freq.tick()
00075
00076 def clear_window(self):
00077 """Clears the frequency statistics."""
00078 self.freq.clear()
00079
00080
00081 class TopicDiagnostic(HeaderlessTopicDiagnostic):
00082 """A class to facilitate making diagnostics for a topic using a
00083 FrequencyStatus and TimeStampStatus.
00084 """
00085
00086 def __init__(self, name, diag, freq, stamp):
00087 """Constructs a TopicDiagnostic.
00088
00089 @param name The name of the topic that is being diagnosed.
00090
00091 @param diag The diagnostic_updater that the CompositeDiagnosticTask
00092 should add itself to.
00093
00094 @param freq The parameters for the FrequencyStatus class that will be
00095 computing statistics.
00096
00097 @param stamp The parameters for the TimeStampStatus class that will be
00098 computing statistics.
00099 """
00100
00101 HeaderlessTopicDiagnostic.__init__(self, name, diag, freq)
00102 self.stamp = TimeStampStatus(stamp)
00103 self.addTask(self.stamp)
00104
00105 def tick(self, stamp):
00106 """Collects statistics and publishes the message.
00107
00108 @param stamp Timestamp to use for interval computation by the
00109 TimeStampStatus class.
00110 """
00111 self.stamp.tick(stamp)
00112 HeaderlessTopicDiagnostic.tick(self)
00113
00114
00115 class DiagnosedPublisher(TopicDiagnostic):
00116 """A TopicDiagnostic combined with a ros::Publisher.
00117
00118 For a standard ros::Publisher, this class allows the ros::Publisher and
00119 the TopicDiagnostic to be combined for added convenience.
00120 """
00121
00122 def __init__(self, pub, diag, freq, stamp):
00123 """Constructs a DiagnosedPublisher.
00124
00125 @param pub The publisher on which statistics are being collected.
00126
00127 @param diag The diagnostic_updater that the CompositeDiagnosticTask
00128 should add itself to.
00129
00130 @param freq The parameters for the FrequencyStatus class that will be
00131 computing statistics.
00132
00133 @param stamp The parameters for the TimeStampStatus class that will be
00134 computing statistics.
00135 """
00136 TopicDiagnostic.__init__(self, pub.name, diag, freq, stamp)
00137 self.publisher = pub
00138
00139 def publish(self, message):
00140 """Collects statistics and publishes the message.
00141
00142 The timestamp to be used by the TimeStampStatus class will be
00143 extracted from message.header.stamp.
00144 """
00145 self.tick(message.header.stamp)
00146 self.publisher.publish(message)