diagnostic_updater/publisher.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2009, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 // Author: Blaise Gassend
37 #ifndef __DIAGNOSTIC_UPDATER__DRIVER_H__
38 #define __DIAGNOSTIC_UPDATER__DRIVER_H__
39 
40 #include <ros/publisher.h>
41 #include <ros/subscription.h>
42 #include <diagnostic_updater/update_functions.h>
43 
44 namespace diagnostic_updater
45 {
46 
56 class HeaderlessTopicDiagnostic : public CompositeDiagnosticTask
57 {
58 public:
72  std::string name,
75  CompositeDiagnosticTask(name + " topic status"),
76  freq_(freq)
77  {
78  addTask(&freq_);
79  diag.add(*this);
80  }
81 
83  {}
84 
89  virtual void tick()
90  {
91  freq_.tick();
92  }
93 
98  virtual void clear_window()
99  {
100  freq_.clear();
101  }
102 
103 private:
105 };
106 
112 class TopicDiagnostic : public HeaderlessTopicDiagnostic
113 {
114 public:
131  std::string name,
135  HeaderlessTopicDiagnostic(name, diag, freq),
136  stamp_(stamp)
137  {
138  addTask(&stamp_);
139  }
140 
141  virtual ~TopicDiagnostic()
142  {}
143 
149  virtual void tick() { ROS_FATAL("tick(void) has been called on a TopicDiagnostic. This is never correct. Use tick(ros::Time &) instead."); }
150 
157  virtual void tick(const ros::Time &stamp)
158  {
159  stamp_.tick(stamp);
161  }
162 
163 private:
164  TimeStampStatus stamp_;
165 };
166 
174 template<class T>
175 class DiagnosedPublisher : public TopicDiagnostic
176 {
177 public:
197  TopicDiagnostic(pub.getTopic(), diag, freq, stamp),
198  publisher_(pub)
199  {}
200 
201  virtual ~DiagnosedPublisher()
202  {}
203 
210  virtual void publish(const std::shared_ptr<T>& message) {
211  tick(message->header.stamp); publisher_.publish(message); }
212 
219  virtual void publish(const T& message) { tick(message.header.stamp);
221 
226  {
227  return publisher_;
228  }
229 
234  {
235  publisher_ = pub;
236  }
237 
238 private:
240 };
241 
242 };
243 
244 #endif
diagnostic_updater::CompositeDiagnosticTask::addTask
void addTask(DiagnosticTask *t)
diagnostic_updater::FrequencyStatus
A diagnostic task that monitors the frequency of an event.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:110
diagnostic_updater::DiagnosedPublisher::~DiagnosedPublisher
virtual ~DiagnosedPublisher()
ros::Publisher
diagnostic_updater::TimeStampStatusParam
A structure that holds the constructor parameters for the TimeStampStatus class.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:218
diagnostic_updater::HeaderlessTopicDiagnostic::tick
virtual void tick()
diagnostic_updater::DiagnosedPublisher::DiagnosedPublisher
DiagnosedPublisher(const ros::Publisher &pub, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
pub
ros::Publisher pub
Definition: pcl_converter.cpp:73
diagnostic_updater::Updater
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
Definition: eloquent/include/diagnostic_updater/diagnostic_updater.hpp:353
diagnostic_updater::HeaderlessTopicDiagnostic::clear_window
virtual void clear_window()
diagnostic_updater::TopicDiagnostic::TopicDiagnostic
TopicDiagnostic(std::string name, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
diagnostic_updater::FrequencyStatus::tick
void tick()
message
def message(msg, *args, **kwargs)
diagnostic_updater::TopicDiagnostic::tick
virtual void tick()
diagnostic_updater::DiagnosedPublisher::publish
virtual void publish(const boost::shared_ptr< T > &message)
diagnostic_updater::HeaderlessTopicDiagnostic::HeaderlessTopicDiagnostic
HeaderlessTopicDiagnostic(std::string name, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq)
api.setup.name
name
Definition: python/api/setup.py:12
diagnostic_updater::HeaderlessTopicDiagnostic::freq_
diagnostic_updater::FrequencyStatus freq_
Definition: eloquent/include/diagnostic_updater/publisher.hpp:99
diagnostic_updater::TimeStampStatus::tick
void tick(const ros::Time t)
diagnostic_updater
Author: Blaise Gassend.
ROS_FATAL
#define ROS_FATAL(...)
Definition: sick_scan_logging.h:132
diagnostic_updater::TopicDiagnostic::~TopicDiagnostic
virtual ~TopicDiagnostic()
diagnostic_updater::TopicDiagnostic::stamp_
TimeStampStatus stamp_
Definition: eloquent/include/diagnostic_updater/publisher.hpp:164
diagnostic_updater::DiagnosedPublisher::getPublisher
ros::Publisher getPublisher() const
ros::Publisher::getTopic
std::string getTopic() const
Definition: rossimu.cpp:416
ros::Time
diagnostic_updater::CompositeDiagnosticTask::CompositeDiagnosticTask
CompositeDiagnosticTask(const std::string name)
sick_scan_base.h
diagnostic_updater::FrequencyStatus::clear
void clear()
diagnostic_updater::DiagnosedPublisher::setPublisher
void setPublisher(ros::Publisher pub)
diagnostic_updater::HeaderlessTopicDiagnostic::~HeaderlessTopicDiagnostic
virtual ~HeaderlessTopicDiagnostic()
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
diagnostic_updater::DiagnosedPublisher::publisher_
ros::Publisher publisher_
Definition: diagnostic_updater/publisher.h:239
diagnostic_updater::FrequencyStatusParam
A structure that holds the constructor parameters for the FrequencyStatus class.
Definition: eloquent/include/diagnostic_updater/update_functions.hpp:53


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10