foxy/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 #include <utility>
43 
44 #include "diagnostic_msgs/msg/diagnostic_array.hpp"
45 #include "diagnostic_updater/update_functions.hpp"
46 
47 #include "rclcpp/clock.hpp"
48 #include "rclcpp/publisher.hpp"
49 #include "rclcpp/subscription.hpp"
50 
51 namespace
52 {
56 template<typename T, typename = void>
57 struct has_header : public std::false_type
58 {};
59 
63 template<typename T>
64 struct has_header<T,
65  typename std::enable_if<std::is_same<std_msgs::msg::Header,
66  decltype(std::declval<T>().header)>::value>::type>
67  : public std::true_type
68 {};
69 } // namespace
70 
71 namespace diagnostic_updater
72 {
73 
82 class HeaderlessTopicDiagnostic : public CompositeDiagnosticTask
83 {
84 public:
98  std::string name, diagnostic_updater::Updater & diag,
100  : CompositeDiagnosticTask(name + " topic status"), freq_(freq)
101  {
102  addTask(&freq_);
103  diag.add(*this);
104  }
105 
106  virtual ~HeaderlessTopicDiagnostic() {}
107 
112  virtual void tick() {freq_.tick();}
113 
118  virtual void clear_window() {freq_.clear();}
119 
120 private:
122 };
123 
129 class TopicDiagnostic : public HeaderlessTopicDiagnostic
130 {
131 public:
151  std::string name, diagnostic_updater::Updater & diag,
154  const rclcpp::Clock::SharedPtr & clock = std::make_shared<rclcpp::Clock>())
155  : HeaderlessTopicDiagnostic(name, diag, freq),
156  stamp_(stamp, clock),
157  error_logger_(rclcpp::get_logger("TopicDiagnostic_error_logger"))
158  {
159  addTask(&stamp_);
160  }
161 
162  virtual ~TopicDiagnostic() {}
163 
170  virtual void tick()
171  {
172  std::string error_msg = "tick(void) has been called on a TopicDiagnostic.";
173  error_msg += " This is never correct. Use tick(rclcpp::Time &) instead.";
174  RCLCPP_FATAL(error_logger_, error_msg);
175  }
176 
183  virtual void tick(const rclcpp::Time & stamp)
184  {
185  stamp_.tick(stamp);
187  }
188 
189 private:
190  TimeStampStatus stamp_;
191  rclcpp::Logger error_logger_;
192 };
193 
201 template<typename MessageT, typename AllocatorT = std::allocator<void>>
202 class DiagnosedPublisher : public TopicDiagnostic
203 {
204 public:
220  using PublisherT = rclcpp::Publisher<MessageT, AllocatorT>;
221 
223  const typename PublisherT::SharedPtr & pub,
227  : TopicDiagnostic(pub->get_topic_name(), diag, freq, stamp),
228  publisher_(pub)
229  {
230  static_assert(has_header<MessageT>::value, "Message type has to have a header.");
231  }
232 
233  virtual ~DiagnosedPublisher() {}
234 
241  virtual void publish(typename PublisherT::MessageUniquePtr message)
242  {
243  tick(message->header.stamp);
244  publisher_->publish(std::move(message));
245  }
246 
253  virtual void publish(const MessageT & message)
254  {
255  tick(message.header.stamp);
256  publisher_->publish(message);
257  }
258 
262  typename PublisherT::SharedPtr
263  getPublisher() const
264  {
265  return publisher_;
266  }
267 
271  void setPublisher(typename PublisherT::SharedPtr pub)
272  {
273  publisher_ = pub;
274  }
275 
276 private:
277  typename PublisherT::SharedPtr publisher_;
278 };
279 } // namespace diagnostic_updater
280 
281 #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)
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