_publisher.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 # -*- coding: utf-8 -*-
34 
35 """ diagnostic_updater for Python.
36 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
37 """
38 
39 import rospy
40 import threading
41 from ._update_functions import *
42 
43 
45  """A class to facilitate making diagnostics for a topic using a
46  :class:`FrequencyStatus`.
47 
48  The word "headerless" in the class name refers to the fact that it is
49  mainly designed for use with messages that do not have a header, and
50  that cannot therefore be checked using a :class:`TimeStampStatus`.
51  """
52 
53  def __init__(self, name, diag, freq):
54  """Constructs a :class:`HeaderlessTopicDiagnostic`.
55 
56  :param str name: The name of the topic that is being diagnosed.
57 
58  :param diagnostic_updater.Updater diag: The :class:`Updater` that the :class:`CompositeDiagnosticTask`
59  should add itself to.
60 
61  :param diagnostic_updater.FrequencyStatusParam freq: The parameters for the :class:`FrequencyStatus`
62  class that will be computing statistics.
63  """
64  CompositeDiagnosticTask.__init__(self, name + " topic status")
65  self.diag = diag
66  self.freq = FrequencyStatus(freq)
67  self.addTask(self.freq)
68  self.diag.add(self)
69 
70  def tick(self):
71  """Signals that a publication has occurred."""
72  self.freq.tick()
73 
74  def clear_window(self):
75  """Clears the frequency statistics."""
76  self.freq.clear()
77 
78 
80  """A class to facilitate making diagnostics for a topic using a
81  :class:`FrequencyStatus` and :class:`TimeStampStatus`.
82  """
83 
84  def __init__(self, name, diag, freq, stamp):
85  """Constructs a :class:`TopicDiagnostic`.
86 
87  :param str name: The name of the topic that is being diagnosed.
88 
89  :param diagnostic_updater.Updater diag: The :class:`Updater` that the :class:`CompositeDiagnosticTask`
90  should add itself to.
91 
92  :param diagnostic_updater.FrequencyStatusParam freq: The parameters for the :class:`FrequencyStatus`
93  class that will be computing statistics.
94 
95  :param diagnostic_updater.TimeStampStatusParam stamp: The parameters for the :class:`TimeStampStatus`
96  class that will be computing statistics.
97  """
98 
99  HeaderlessTopicDiagnostic.__init__(self, name, diag, freq)
100  self.stamp = TimeStampStatus(stamp)
101  self.addTask(self.stamp)
102 
103  def tick(self, stamp):
104  """Collects statistics and publishes the message.
105 
106  :param stamp: Timestamp to use for interval computation by the
107  :class:`TimeStampStatus` class.
108  :type stamp: float or rospy.Time
109  """
110  self.stamp.tick(stamp)
111  HeaderlessTopicDiagnostic.tick(self)
112 
113 
115  """A :class:`TopicDiagnostic` combined with a :class:`rospy.Publisher`.
116 
117  For a standard :class:`rospy.Publisher`, this class allows the :class:`rospy.Publisher` and
118  the :class:`TopicDiagnostic` to be combined for added convenience.
119  """
120 
121  def __init__(self, pub, diag, freq, stamp):
122  """Constructs a :class:`DiagnosedPublisher`.
123 
124  :param rospy.Publisher pub: The publisher on which statistics are being collected.
125 
126  :param diagnostic_updater.Updater diag: The :class:`Updater` that the :class:`CompositeDiagnosticTask`
127  should add itself to.
128 
129  :param diagnostic_updater.FrequencyStatusParam freq: The parameters for the :class:`FrequencyStatus`
130  class that will be computing statistics.
131 
132  :param diagnostic_updater.TimeStampStatusParam stamp: The parameters for the :class:`TimeStampStatus`
133  class that will be computing statistics.
134  """
135  TopicDiagnostic.__init__(self, pub.name, diag, freq, stamp)
136  self.publisher = pub
137 
138  def publish(self, message):
139  """Collects statistics and publishes the message.
140 
141  The timestamp to be used by the :class:`TimeStampStatus` class will be
142  extracted from `message.header.stamp`.
143 
144  :param genpy.Message message: The message to be published.
145  """
146  self.tick(message.header.stamp)
147  self.publisher.publish(message)
diagnostic_updater._diagnostic_updater.CompositeDiagnosticTask.addTask
def addTask(self, t)
Definition: _diagnostic_updater.py:150
diagnostic_updater._publisher.TopicDiagnostic.tick
def tick(self, stamp)
Definition: _publisher.py:103
diagnostic_updater._update_functions.TimeStampStatus
Definition: _update_functions.py:167
diagnostic_updater._publisher.HeaderlessTopicDiagnostic.__init__
def __init__(self, name, diag, freq)
Definition: _publisher.py:53
diagnostic_updater._publisher.HeaderlessTopicDiagnostic.diag
diag
Definition: _publisher.py:65
diagnostic_updater._update_functions.FrequencyStatus
Definition: _update_functions.py:82
diagnostic_updater._diagnostic_updater.CompositeDiagnosticTask
Definition: _diagnostic_updater.py:107
diagnostic_updater._publisher.HeaderlessTopicDiagnostic.tick
def tick(self)
Definition: _publisher.py:70
diagnostic_updater._publisher.HeaderlessTopicDiagnostic.clear_window
def clear_window(self)
Definition: _publisher.py:74
diagnostic_updater._publisher.DiagnosedPublisher
Definition: _publisher.py:114
diagnostic_updater._publisher.TopicDiagnostic.__init__
def __init__(self, name, diag, freq, stamp)
Definition: _publisher.py:84
diagnostic_updater._publisher.DiagnosedPublisher.__init__
def __init__(self, pub, diag, freq, stamp)
Definition: _publisher.py:121
diagnostic_updater._publisher.DiagnosedPublisher.publish
def publish(self, message)
Definition: _publisher.py:138
diagnostic_updater._publisher.HeaderlessTopicDiagnostic.freq
freq
Definition: _publisher.py:66
diagnostic_updater._publisher.TopicDiagnostic
Definition: _publisher.py:79
diagnostic_updater._publisher.HeaderlessTopicDiagnostic
Definition: _publisher.py:44
diagnostic_updater._publisher.DiagnosedPublisher.publisher
publisher
Definition: _publisher.py:136
diagnostic_updater._publisher.TopicDiagnostic.stamp
stamp
Definition: _publisher.py:100


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Tue May 6 2025 02:17:37