eloquent/include/diagnostic_updater/publisher.hpp
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__PUBLISHER_HPP_
38 #define DIAGNOSTIC_UPDATER__PUBLISHER_HPP_
39 
40 #include <memory>
41 #include <string>
42 
43 #include "diagnostic_msgs/msg/diagnostic_array.hpp"
44 #include "diagnostic_updater/update_functions.hpp"
45 
46 #include "rclcpp/publisher.hpp"
47 #include "rclcpp/subscription.hpp"
48 
49 namespace diagnostic_updater
50 {
51 
60 class HeaderlessTopicDiagnostic : public CompositeDiagnosticTask
61 {
62 public:
76  std::string name, diagnostic_updater::Updater & diag,
78  : CompositeDiagnosticTask(name + " topic status"), freq_(freq)
79  {
80  addTask(&freq_);
81  diag.add(*this);
82  }
83 
84  virtual ~HeaderlessTopicDiagnostic() {}
85 
90  virtual void tick() {freq_.tick();}
91 
96  virtual void clear_window() {freq_.clear();}
97 
98 private:
100 };
101 
107 class TopicDiagnostic : public HeaderlessTopicDiagnostic
108 {
109 public:
126  std::string name, diagnostic_updater::Updater & diag,
129  : HeaderlessTopicDiagnostic(name, diag, freq),
130  stamp_(stamp),
131  error_logger_(rclcpp::get_logger("TopicDiagnostic_error_logger"))
132  {
133  addTask(&stamp_);
134  }
135 
136  virtual ~TopicDiagnostic() {}
137 
144  virtual void tick()
145  {
146  std::string error_msg = "tick(void) has been called on a TopicDiagnostic.";
147  error_msg += " This is never correct. Use tick(rclcpp::Time &) instead.";
148  RCLCPP_FATAL(error_logger_, error_msg);
149  }
150 
157  virtual void tick(const rclcpp::Time & stamp)
158  {
159  stamp_.tick(stamp);
161  }
162 
163 private:
164  TimeStampStatus stamp_;
165  rclcpp::Logger error_logger_;
166 };
167 
175 template<class T>
176 class DiagnosedPublisher : public TopicDiagnostic
177 {
178 public:
195  const rclcpp::Publisher<
200  : TopicDiagnostic(pub->get_topic_name(), diag, freq, stamp),
201  publisher_(pub) {}
202 
203  virtual ~DiagnosedPublisher() {}
204 
211  virtual void publish(const std::shared_ptr<T> & message)
212  {
213  tick(message->header.stamp);
215  }
216 
223  virtual void publish(const T & message)
224  {
225  tick(message.header.stamp);
227  }
228 
232  rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr
233  getPublisher() const
234  {
235  return publisher_;
236  }
237 
241  void setPublisher(
242  rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr pub)
243  {
244  publisher_ = pub;
245  }
246 
247 private:
248  rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr publisher_;
249 };
250 } // namespace diagnostic_updater
251 
252 #endif // DIAGNOSTIC_UPDATER__PUBLISHER_HPP_
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()
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.
diagnostic_updater::TopicDiagnostic::~TopicDiagnostic
virtual ~TopicDiagnostic()
std_msgs::Time
::std_msgs::Time_< std::allocator< void > > Time
Definition: Time.h:48
diagnostic_updater::TopicDiagnostic::stamp_
TimeStampStatus stamp_
Definition: eloquent/include/diagnostic_updater/publisher.hpp:164
diagnostic_updater::DiagnosedPublisher::getPublisher
ros::Publisher getPublisher() const
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_msgs::DiagnosticArray
::diagnostic_msgs::DiagnosticArray_< std::allocator< void > > DiagnosticArray
Definition: DiagnosticArray.h:55
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