galactic/include/diagnostic_updater/publisher.hpp
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__PUBLISHER_HPP_
37 #define DIAGNOSTIC_UPDATER__PUBLISHER_HPP_
38 
39 #include <memory>
40 #include <string>
41 #include <utility>
42 
43 #include "diagnostic_msgs/msg/diagnostic_array.hpp"
44 #include "diagnostic_updater/update_functions.hpp"
45 
46 #include "rclcpp/clock.hpp"
47 #include "rclcpp/publisher.hpp"
48 #include "rclcpp/subscription.hpp"
49 
50 namespace
51 {
55 template<typename T, typename = void>
56 struct has_header : public std::false_type
57 {};
58 
62 template<typename T>
63 struct has_header<T,
64  typename std::enable_if<std::is_same<std_msgs::msg::Header,
65  decltype(std::declval<T>().header)>::value>::type>
66  : public std::true_type
67 {};
68 } // namespace
69 
70 namespace diagnostic_updater
71 {
72 
81 class HeaderlessTopicDiagnostic : public CompositeDiagnosticTask
82 {
83 public:
97  std::string name, diagnostic_updater::Updater & diag,
99  : CompositeDiagnosticTask(name + " topic status"), freq_(freq)
100  {
101  addTask(&freq_);
102  diag.add(*this);
103  }
104 
105  virtual ~HeaderlessTopicDiagnostic() {}
106 
111  virtual void tick() {freq_.tick();}
112 
117  virtual void clear_window() {freq_.clear();}
118 
119 private:
121 };
122 
128 class TopicDiagnostic : public HeaderlessTopicDiagnostic
129 {
130 public:
150  std::string name, diagnostic_updater::Updater & diag,
153  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
154  : HeaderlessTopicDiagnostic(name, diag, freq),
155  stamp_(stamp, clock),
156  error_logger_(rclcpp::get_logger("TopicDiagnostic_error_logger"))
157  {
158  addTask(&stamp_);
159  }
160 
161  virtual ~TopicDiagnostic() {}
162 
169  virtual void tick()
170  {
171  std::string error_msg = "tick(void) has been called on a TopicDiagnostic.";
172  error_msg += " This is never correct. Use tick(rclcpp::Time &) instead.";
173  RCLCPP_FATAL(error_logger_, "%s", error_msg.c_str());
174  }
175 
182  virtual void tick(const rclcpp::Time & stamp)
183  {
184  stamp_.tick(stamp);
186  }
187 
188 private:
189  TimeStampStatus stamp_;
190  rclcpp::Logger error_logger_;
191 };
192 
200 template<typename MessageT, typename AllocatorT = std::allocator<void>>
201 class DiagnosedPublisher : public TopicDiagnostic
202 {
203 public:
219  using PublisherT = rclcpp::Publisher<MessageT, AllocatorT>;
220 
222  const typename PublisherT::SharedPtr & pub,
226  : TopicDiagnostic(pub->get_topic_name(), diag, freq, stamp),
227  publisher_(pub)
228  {
229  static_assert(has_header<MessageT>::value, "Message type has to have a header.");
230  }
231 
232  virtual ~DiagnosedPublisher() {}
233 
240  virtual void publish(typename PublisherT::MessageUniquePtr message)
241  {
242  tick(message->header.stamp);
243  publisher_->publish(std::move(message));
244  }
245 
252  virtual void publish(const MessageT & message)
253  {
254  tick(message.header.stamp);
255  publisher_->publish(message);
256  }
257 
261  typename PublisherT::SharedPtr
262  getPublisher() const
263  {
264  return publisher_;
265  }
266 
270  void setPublisher(typename PublisherT::SharedPtr pub)
271  {
272  publisher_ = pub;
273  }
274 
275 private:
276  typename PublisherT::SharedPtr publisher_;
277 };
278 } // namespace diagnostic_updater
279 
280 #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)
test_server.type
type
Definition: test_server.py:210
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
std
diagnostic_updater::CompositeDiagnosticTask::CompositeDiagnosticTask
CompositeDiagnosticTask(const std::string name)
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