publisher.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 // Author: Blaise Gassend
36 #ifndef __DIAGNOSTIC_UPDATER__DRIVER_H__
37 #define __DIAGNOSTIC_UPDATER__DRIVER_H__
38 
39 #include <ros/publisher.h>
40 #include <ros/subscription.h>
42 
43 namespace diagnostic_updater
44 {
45 
55 class HeaderlessTopicDiagnostic : public CompositeDiagnosticTask
56 {
57 public:
71  std::string name,
74  CompositeDiagnosticTask(name + " topic status"),
75  freq_(freq)
76  {
77  addTask(&freq_);
78  diag.add(*this);
79  }
80 
82  {}
83 
88  virtual void tick()
89  {
90  freq_.tick();
91  }
92 
97  virtual void clear_window()
98  {
99  freq_.clear();
100  }
101 
102 private:
104 };
105 
111 class TopicDiagnostic : public HeaderlessTopicDiagnostic
112 {
113 public:
130  std::string name,
134  HeaderlessTopicDiagnostic(name, diag, freq),
135  stamp_(stamp)
136  {
137  addTask(&stamp_);
138  }
139 
140  virtual ~TopicDiagnostic()
141  {}
142 
148  virtual void tick() { ROS_FATAL("tick(void) has been called on a TopicDiagnostic. This is never correct. Use tick(ros::Time &) instead."); }
149 
156  virtual void tick(const ros::Time &stamp)
157  {
158  stamp_.tick(stamp);
160  }
161 
162 private:
164 };
165 
173 template<class T>
174 class DiagnosedPublisher : public TopicDiagnostic
175 {
176 public:
196  TopicDiagnostic(pub.getTopic(), diag, freq, stamp),
197  publisher_(pub)
198  {}
199 
200  virtual ~DiagnosedPublisher()
201  {}
202 
209  virtual void publish(const boost::shared_ptr<T>& message) {
210  tick(message->header.stamp); publisher_.publish(message); }
211 
218  virtual void publish(const T& message) { tick(message.header.stamp);
219  publisher_.publish(message); }
220 
225  {
226  return publisher_;
227  }
228 
233  {
234  publisher_ = pub;
235  }
236 
237 private:
239 };
240 
241 }
242 
243 #endif
diagnostic_updater::CompositeDiagnosticTask::addTask
void addTask(DiagnosticTask *t)
Adds a child CompositeDiagnosticTask.
Definition: diagnostic_updater.h:219
diagnostic_updater::FrequencyStatus
A diagnostic task that monitors the frequency of an event.
Definition: update_functions.h:136
diagnostic_updater::DiagnosedPublisher::~DiagnosedPublisher
virtual ~DiagnosedPublisher()
Definition: publisher.h:232
ros::Publisher
boost::shared_ptr
diagnostic_updater::TimeStampStatusParam
A structure that holds the constructor parameters for the TimeStampStatus class.
Definition: update_functions.h:257
diagnostic_updater::HeaderlessTopicDiagnostic::tick
virtual void tick()
Signals that a publication has occurred.
Definition: publisher.h:152
diagnostic_updater::DiagnosedPublisher::DiagnosedPublisher
DiagnosedPublisher(const ros::Publisher &pub, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
Constructs a DiagnosedPublisher.
Definition: publisher.h:224
diagnostic_updater::TimeStampStatus
Diagnostic task to monitor the interval between events.
Definition: update_functions.h:298
diagnostic_updater::Updater
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
Definition: diagnostic_updater.h:395
update_functions.h
subscription.h
diagnostic_updater::HeaderlessTopicDiagnostic::clear_window
virtual void clear_window()
Clears the frequency statistics.
Definition: publisher.h:161
diagnostic_updater::TopicDiagnostic::TopicDiagnostic
TopicDiagnostic(std::string name, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
Constructs a TopicDiagnostic.
Definition: publisher.h:161
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
publisher.h
diagnostic_updater::FrequencyStatus::tick
void tick()
Signals that an event has occurred.
Definition: update_functions.h:193
diagnostic_updater::TopicDiagnostic::tick
virtual void tick()
Definition: publisher.h:180
diagnostic_updater::DiagnosedPublisher::publish
virtual void publish(const boost::shared_ptr< T > &message)
Collects statistics and publishes the message.
Definition: publisher.h:241
diagnostic_updater::HeaderlessTopicDiagnostic::HeaderlessTopicDiagnostic
HeaderlessTopicDiagnostic(std::string name, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq)
Constructs a HeaderlessTopicDiagnostic.
Definition: publisher.h:134
diagnostic_updater::HeaderlessTopicDiagnostic::freq_
diagnostic_updater::FrequencyStatus freq_
Definition: publisher.h:167
diagnostic_updater
Author: Blaise Gassend.
Definition: diagnostic_updater.h:51
diagnostic_updater::DiagnosedPublisher
A TopicDiagnostic combined with a ros::Publisher.
Definition: publisher.h:206
diagnostic_updater::TopicDiagnostic::~TopicDiagnostic
virtual ~TopicDiagnostic()
Definition: publisher.h:172
diagnostic_updater::HeaderlessTopicDiagnostic
A class to facilitate making diagnostics for a topic using a FrequencyStatus.
Definition: publisher.h:87
ROS_FATAL
#define ROS_FATAL(...)
diagnostic_updater::TopicDiagnostic::stamp_
TimeStampStatus stamp_
Definition: publisher.h:195
diagnostic_updater::TopicDiagnostic
A class to facilitate making diagnostics for a topic using a FrequencyStatus and TimeStampStatus.
Definition: publisher.h:143
diagnostic_updater::DiagnosedPublisher::getPublisher
ros::Publisher getPublisher() const
Returns the publisher.
Definition: publisher.h:256
ros::Time
diagnostic_updater::CompositeDiagnosticTask::CompositeDiagnosticTask
CompositeDiagnosticTask(const std::string name)
Constructs a CompositeDiagnosticTask with the given name.
Definition: diagnostic_updater.h:185
diagnostic_updater::FrequencyStatus::clear
void clear()
Resets the statistics.
Definition: update_functions.h:175
diagnostic_updater::DiagnosedPublisher::setPublisher
void setPublisher(ros::Publisher pub)
Changes the publisher.
Definition: publisher.h:264
diagnostic_updater::HeaderlessTopicDiagnostic::~HeaderlessTopicDiagnostic
virtual ~HeaderlessTopicDiagnostic()
Definition: publisher.h:145
diagnostic_updater::TimeStampStatus::tick
void tick(double stamp)
Signals an event. Timestamp stored as a double.
Definition: update_functions.h:354
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
Add a DiagnosticTask embodied by a name and function to the DiagnosticTaskVector.
Definition: diagnostic_updater.h:289
diagnostic_updater::DiagnosedPublisher::publisher_
ros::Publisher publisher_
Definition: publisher.h:270
diagnostic_updater::FrequencyStatusParam
A structure that holds the constructor parameters for the FrequencyStatus class.
Definition: update_functions.h:83


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Tue Nov 15 2022 03:17:19