14 #include <type_traits>
16 #include <boost/function.hpp>
17 #include <boost/shared_ptr.hpp>
56 template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
71 explicit DiagnosedPubSub(const ::std::string& name, const ::cras::TopicStatusParam<Message>& diagParams);
79 const ::cras::SimpleTopicStatusParam<Message>& defaultParams);
99 virtual ::std::shared_ptr<::cras::TopicStatus<Message>>
getDiagnosticTask()
const;
109 template <class M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value,
bool> EnableM =
true>
120 template <class M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader<M>::value,
bool> EnableM =
true>
125 ::std::shared_ptr<::cras::TopicStatus<Message>>
diag {
nullptr};
135 template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
153 const ::cras::TopicStatusParam<Message>& diagParams);
163 const ::cras::SimpleTopicStatusParam<Message>& defaultParams);
184 const ::ros::Rate& defaultMinRate, const ::ros::Rate& defaultMaxRate);
193 virtual void publish(
const typename Message::Ptr& message);
199 virtual void publish(
const Message& message);
229 template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
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 = {});
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 = {});
278 template <typename C, typename EnableC = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
281 const ::std::string& topic, uint32_t queue_size,
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 = {});
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 = {});
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,
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,
388 ::boost::function<void(
const Message&)>
addTick(const ::std::function<
void(
const Message&)>& fn);
395 ::boost::function<void(
const typename Message::Ptr&)>
addTick(
396 const ::std::function<
void(
const typename Message::Ptr&)>& fn);
403 ::boost::function<void(const ::ros::MessageEvent<Message>&)>
addTick(
404 const ::std::function<
void(const ::ros::MessageEvent<Message>&)>& fn);
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);
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);
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);
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);
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);
470 #if __cpp_deduction_guides
472 template <typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
478 template <typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
484 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
490 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
496 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
502 template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
511 #include <cras_cpp_common/diag_utils/impl/diagnosed_pub_sub.hpp>