_publisher.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 
00033 # -*- coding: utf-8 -*-
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)


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Fri Aug 28 2015 10:29:57