diagnosed_pub_sub.hpp
Go to the documentation of this file.
1 #pragma once
2 
11 #include <functional>
12 #include <memory>
13 #include <string>
14 #include <type_traits>
15 
16 #include <boost/function.hpp>
17 #include <boost/shared_ptr.hpp>
18 
20 #include <ros/forwards.h>
21 #include <ros/message_event.h>
22 #include <ros/message_traits.h>
23 #include <ros/node_handle.h>
24 #include <ros/publisher.h>
25 #include <ros/rate.h>
26 #include <ros/subscriber.h>
27 #include <ros/subscribe_options.h>
28 
34 
35 namespace cras
36 {
37 
56 template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
58 {
59 public:
64  explicit DiagnosedPubSub(const ::std::shared_ptr<::cras::TopicStatus<Message>>& diag);
65 
71  explicit DiagnosedPubSub(const ::std::string& name, const ::cras::TopicStatusParam<Message>& diagParams);
72 
79  const ::cras::SimpleTopicStatusParam<Message>& defaultParams);
80 
86 
87  virtual ~DiagnosedPubSub() = default;
88 
94 
99  virtual ::std::shared_ptr<::cras::TopicStatus<Message>> getDiagnosticTask() const;
100 
101 protected:
109  template <class M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value, bool> EnableM = true>
110  void addDelayParams(::cras::SimpleTopicStatusParam<Message>& topicStatusParam,
112 
120  template <class M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader<M>::value, bool> EnableM = true>
121  void addDelayParams(::cras::SimpleTopicStatusParam<Message>& topicStatusParam,
123 
125  ::std::shared_ptr<::cras::TopicStatus<Message>> diag {nullptr};
126 };
127 
135 template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
137 {
138 public:
144  DiagnosedPublisher(const ::ros::Publisher &pub, const ::std::shared_ptr<::cras::TopicStatus<Message>>& diag);
145 
152  DiagnosedPublisher(const ::ros::Publisher &pub, const ::std::string& name,
153  const ::cras::TopicStatusParam<Message>& diagParams);
154 
162  DiagnosedPublisher(const ::ros::Publisher &pub, const ::cras::BoundParamHelperPtr& params,
163  const ::cras::SimpleTopicStatusParam<Message>& defaultParams);
164 
171  DiagnosedPublisher(const ::ros::Publisher &pub, const ::cras::BoundParamHelperPtr& params);
172 
173  [[deprecated]]
174  DiagnosedPublisher(const ::ros::Publisher &pub, ::diagnostic_updater::Updater& updater,
176 
177  [[deprecated]]
178  DiagnosedPublisher(const ::ros::Publisher &pub, ::diagnostic_updater::Updater& updater,
179  const ::cras::BoundParamHelperPtr& params, const ::ros::Rate& defaultRate);
180 
181  [[deprecated]]
182  DiagnosedPublisher(const ::ros::Publisher &pub, ::diagnostic_updater::Updater& updater,
183  const ::cras::BoundParamHelperPtr& params, const ::ros::Rate& defaultRate,
184  const ::ros::Rate& defaultMinRate, const ::ros::Rate& defaultMaxRate);
185 
186  [[deprecated]]
187  ::ros::Rate getDesiredRate() const;
188 
193  virtual void publish(const typename Message::Ptr& message);
194 
199  virtual void publish(const Message& message);
200 
205  const ::ros::Publisher& getPublisher() const;
206 
212 
217  void setPublisher(const ::ros::Publisher& pub);
218 
219 protected:
222 };
223 
229 template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
231 {
232 public:
245  template <typename M, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
248  const ::std::string& topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints = {});
249 
261  const ::cras::SimpleTopicStatusParam<Message>& defaultParams,
262  const ::std::string& topic, uint32_t queue_size,
263  const ::boost::function<void(const ::boost::shared_ptr<Message>&)>& cb, ::ros::TransportHints hints = {});
264 
278  template <typename C, typename EnableC = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
281  const ::std::string& topic, uint32_t queue_size,
282  const ::boost::function<void(C)>& cb, ::ros::VoidConstPtr obj = {}, ::ros::TransportHints hints = {});
283 
297  template<typename M, class T, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
300  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M), T* obj, ::ros::TransportHints hints = {});
301 
315  template<typename M, class T, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
318  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M) const, T* obj, ::ros::TransportHints hints = {});
319 
333  template<typename M, class T, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
336  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr<T>& obj,
337  ::ros::TransportHints hints = {});
338 
352  template<typename M, class T, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
355  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr<T>& obj,
356  ::ros::TransportHints hints = {});
357 
368  const ::cras::SimpleTopicStatusParam<Message>& defaultParams, ::ros::SubscribeOptions& options);
369 
374  const ::ros::Subscriber& getSubscriber() const;
375 
381 
382 protected:
388  ::boost::function<void(const Message&)> addTick(const ::std::function<void(const Message&)>& fn);
389 
395  ::boost::function<void(const typename Message::Ptr&)> addTick(
396  const ::std::function<void(const typename Message::Ptr&)>& fn);
397 
403  ::boost::function<void(const ::ros::MessageEvent<Message>&)> addTick(
404  const ::std::function<void(const ::ros::MessageEvent<Message>&)>& fn);
405 
414  template <typename T, typename M, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
415  ::boost::function<void(M)> addTick(const ::std::function<void(M)>& fn, T);
416 
426  template <typename T, typename M, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
427  ::boost::function<void(M)> addTick(void(T::*fn)(M), T* obj);
428 
438  template <typename T, typename M, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
439  ::boost::function<void(M)> addTick(void(T::*fn)(M), const ::boost::shared_ptr<T>& obj);
440 
450  template <typename T, typename M, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
451  ::boost::function<void(M)> addTick(void(T::*fn)(M) const, T* obj);
452 
462  template <typename T, typename M, typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
463  ::boost::function<void(M)> addTick(void(T::*fn)(M) const, const ::boost::shared_ptr<T>& obj);
464 
467 };
468 
469 // Class template deduction guides allow leaving out the type parameter when declaring a DiagnosedSubscriber. C++17 only
470 #if __cpp_deduction_guides
471 
472 template <typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
474  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>&, const ::std::string&, uint32_t, void(*)(M),
475  ::ros::TransportHints = {})
476  -> DiagnosedSubscriber<::cras::BaseMessage<M>>;
477 
478 template <typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
479 DiagnosedSubscriber(::ros::NodeHandle, const ::cras::BoundParamHelperPtr&,
480  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<C>>&, const ::std::string&, uint32_t,
481  const ::boost::function<void(C)>&, ::ros::VoidConstPtr = {}, ::ros::TransportHints = {})
482  -> DiagnosedSubscriber<::cras::BaseMessage<C>>;
483 
484 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
485 DiagnosedSubscriber(::ros::NodeHandle, const ::cras::BoundParamHelperPtr&,
486  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>&, const ::std::string&, uint32_t,
487  void(T::*)(M), T*, ::ros::TransportHints = {})
488  -> DiagnosedSubscriber<::cras::BaseMessage<M>>;
489 
490 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
491 DiagnosedSubscriber(::ros::NodeHandle, const ::cras::BoundParamHelperPtr&,
492  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>&, const ::std::string&, uint32_t,
493  void(T::*)(M) const, T*, ::ros::TransportHints = {})
494  -> DiagnosedSubscriber<::cras::BaseMessage<M>>;
495 
496 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
497 DiagnosedSubscriber(::ros::NodeHandle, const ::cras::BoundParamHelperPtr&,
498  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>&, const ::std::string&, uint32_t,
499  void(T::*)(M), const ::boost::shared_ptr<T>&, ::ros::TransportHints = {})
500  -> DiagnosedSubscriber<::cras::BaseMessage<M>>;
501 
502 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
503 DiagnosedSubscriber(::ros::NodeHandle, const ::cras::BoundParamHelperPtr&,
504  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>&, const ::std::string&, uint32_t,
505  void(T::*)(M) const, const ::boost::shared_ptr<T>&, ::ros::TransportHints = {})
506  -> DiagnosedSubscriber<::cras::BaseMessage<M>>;
507 
508 #endif
509 }
510 
511 #include <cras_cpp_common/diag_utils/impl/diagnosed_pub_sub.hpp>
cras::SimpleTopicStatusParam
::std::conditional_t<::ros::message_traits::HasHeader< Message >::value, ::cras::SimpleTopicStatusParamWithHeader, ::cras::SimpleTopicStatusParamNoHeader > SimpleTopicStatusParam
Helper struct for easy brace-initialization of TopicStatusParam objects.
Definition: topic_status_param.hpp:80
forwards.h
cras::DiagnosedPublisher::getPublisher
const ::ros::Publisher & getPublisher() const
Get the ROS publisher.
node_handle.h
message_utils.hpp
Utilities for working with ROS message files.
boost::shared_ptr< void const >
cras
Definition: any.hpp:15
cras::BoundParamHelperPtr
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
Definition: bound_param_helper.hpp:24
cras::DiagnosedPublisher
Wrapper for ROS publisher that automatically diagnoses the rate and delay of published messages.
Definition: diagnosed_pub_sub.hpp:136
cras::DiagnosedPubSub::attach
virtual void attach(::diagnostic_updater::Updater &updater)
Add the diagnostic task to the given updater.
diagnostic_updater::Updater
ros::TransportHints
cras::DiagnosedPublisher::publisher
::ros::Publisher publisher
The ROS publisher.
Definition: diagnosed_pub_sub.hpp:221
bound_param_helper.hpp
Bound param helper (allows omitting the param adapter in each getParam call).
cras::TopicStatus
Diagnostic task for topic frequency and timestamp delay (combining FrequencyStatus and TimeStampStatu...
Definition: topic_status.hpp:34
publisher.h
cras::DiagnosedPubSub
Base for ROS publisher and subscriber with automatic message rate and delay diagnostics.
Definition: diagnosed_pub_sub.hpp:57
diagnostic_updater.h
cras::DiagnosedPublisher::getDesiredRate
::ros::Rate getDesiredRate() const
cras::DiagnosedPubSub::~DiagnosedPubSub
virtual ~DiagnosedPubSub()=default
cras::DiagnosedPublisher::DiagnosedPublisher
DiagnosedPublisher(const ::ros::Publisher &pub, const ::std::shared_ptr<::cras::TopicStatus< Message >> &diag)
Add the given diagnostic task to the publisher.
type_utils.hpp
Utilities for working with C++ types.
cras::DiagnosedPubSub::getDiagnosticTask
virtual ::std::shared_ptr<::cras::TopicStatus< Message > > getDiagnosticTask() const
Get the topic diagnostic task.
message_traits.h
updater
updater
subscriber.h
cras::DiagnosedSubscriber::getSubscriber
const ::ros::Subscriber & getSubscriber() const
Get the created ROS subscriber.
cras::DiagnosedPubSub::diag
::std::shared_ptr<::cras::TopicStatus< Message > > diag
The diagnostic task.
Definition: diagnosed_pub_sub.hpp:125
cras::DiagnosedSubscriber::DiagnosedSubscriber
DiagnosedSubscriber(::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
Subscribe to the given topic reading diagnostic task configuration from ROS parameters.
cras::DiagnosedSubscriber
Wrapper for ROS subscriber that automatically diagnoses the rate and delay of received messages.
Definition: diagnosed_pub_sub.hpp:230
rate.h
ros::Publisher
cras::DiagnosedPubSub::DiagnosedPubSub
DiagnosedPubSub(const ::std::shared_ptr<::cras::TopicStatus< Message >> &diag)
Use the given diagnostic task to diagnose the publisher/subscriber.
cras::DiagnosedPublisher::publish
virtual void publish(const typename Message::Ptr &message)
Publish a message.
cras::DiagnosedSubscriber::subscriber
::ros::Subscriber subscriber
The ROS subscriber.
Definition: diagnosed_pub_sub.hpp:466
cras::DiagnosedSubscriber::addTick
::boost::function< void(const Message &)> addTick(const ::std::function< void(const Message &)> &fn)
Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().
ros::SubscribeOptions
cras::DiagnosedPublisher::setPublisher
void setPublisher(const ::ros::Publisher &pub)
Change the ROS publisher.
cras::DiagnosedPubSub::addDelayParams
void addDelayParams(::cras::SimpleTopicStatusParam< Message > &topicStatusParam, const ::cras::BoundParamHelperPtr &params)
When configuring from ROS params, load the delay configuration.
ros::Rate
topic_status.hpp
Diagnostic task for topic frequency and timestamp delay (combining FrequencyStatus and TimeStampStatu...
ros::Subscriber
topic_status_param.hpp
Definitions of parameters for a TopicStatus diagnostic task.
message_event.h
subscribe_options.h
cras::BaseMessage
typename ::ros::ParameterAdapter< M >::Message BaseMessage
Return the base message type of M (i.e. removes MessageEvent, const, &, shared_ptr etc....
Definition: message_utils.hpp:19
ros::NodeHandle


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:03