node_handle_with_diagnostics.h
Go to the documentation of this file.
1 #pragma once
2 
11 #include <memory>
12 #include <string>
13 #include <type_traits>
14 #include <utility>
15 
16 #include <boost/function.hpp>
17 #include <boost/shared_ptr.hpp>
18 
20 #include <ros/advertise_options.h>
21 #include <ros/datatypes.h>
22 #include <ros/forwards.h>
23 #include <ros/message_traits.h>
24 #include <ros/node_handle.h>
25 #include <ros/subscribe_options.h>
26 #include <ros/transport_hints.h>
27 
35 
36 namespace cras
37 {
38 
89 {
90 public:
96  explicit NodeHandleWithDiagnostics(const ::std::string& ns = "", const ::ros::M_string& remappings = {});
97 
103  NodeHandleWithDiagnostics(const ::ros::NodeHandle& parent, const ::std::string& ns);
104 
111  NodeHandleWithDiagnostics(const ::ros::NodeHandle& parent, const ::std::string& ns,
112  const ::ros::M_string& remappings);
113 
114 protected:
120  virtual ::std::string prefixDiagNamespace(const ::std::string& ns) const;
121 
129  virtual ::cras::BoundParamHelperPtr getDiagParams(const ::std::string& diagNs, const ::std::string& topic) const;
130 
131 public:
133  // ADVERTISE METHODS //
135 
148  template <class Message>
149  ::std::unique_ptr<::cras::DiagnosedPublisher<Message>>
151  const ::cras::SimpleTopicStatusParam<Message>& defaultDiagParams, const ::std::string& diagNamespace,
152  const ::std::string& topic, const size_t queueSize, const bool latch = false)
153  {
154  auto pub = this->template advertise<Message>(topic, queueSize, latch);
155  auto result = ::std::make_unique<::cras::DiagnosedPublisher<Message>>(
156  pub, this->getDiagParams(diagNamespace, topic), defaultDiagParams);
157  result->attach(updater);
158  return result;
159  }
160 
171  template <class Message>
172  ::std::unique_ptr<::cras::DiagnosedPublisher<Message>>
174  const ::cras::SimpleTopicStatusParam<Message>& defaultDiagParams, const ::std::string& diagNamespace,
175  ::ros::AdvertiseOptions& options)
176  {
177  const auto topic = options.topic; // make copy of topic before advertise has a chance to change it
178  auto pub = this->advertise(options);
179  auto result = ::std::make_unique<::cras::DiagnosedPublisher<Message>>(
180  pub, this->getDiagParams(diagNamespace, topic), defaultDiagParams);
181  result->attach(updater);
182  return result;
183  }
184 
196  template <class Message>
197  ::std::unique_ptr<::cras::DiagnosedPublisher<Message>>
198  advertiseDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
199  const ::std::string& topic, const size_t queueSize, const bool latch = false)
200  {
201  return this->template advertiseDiagnosed<Message>(updater, ::cras::SimpleTopicStatusParam<Message>(), diagNamespace,
202  topic, queueSize, latch);
203  }
204 
214  template <class Message>
215  ::std::unique_ptr<::cras::DiagnosedPublisher<Message>>
216  advertiseDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
217  ::ros::AdvertiseOptions& options)
218  {
219  return this->template advertiseDiagnosed<Message>(updater, ::cras::SimpleTopicStatusParam<Message>(), diagNamespace,
220  options);
221  }
222 
234  template <class Message>
235  ::std::unique_ptr<::cras::DiagnosedPublisher<Message>>
237  const ::std::string& topic, const size_t queueSize, const bool latch = false)
238  {
239  return this->template advertiseDiagnosed<Message>(updater, "", topic, queueSize, latch);
240  }
241 
251  template <class Message>
252  ::std::unique_ptr<::cras::DiagnosedPublisher<Message>>
254  {
255  return this->template advertiseDiagnosed<Message>(updater, "", options);
256  }
257 
259  // SUBSCRIBE METHODS //
261 
274  template <typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
275  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
277  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>& defaultDiagParams, const ::std::string& diagNamespace,
278  const ::std::string& topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints = {})
279  {
280  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>(
281  new ::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>(
282  *this, this->getDiagParams(diagNamespace, topic), defaultDiagParams, topic, queue_size, cb, hints));
283  result->attach(updater);
284  return ::std::move(result);
285  }
286 
299  template <typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
300  ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>
302  const ::cras::SimpleTopicStatusParam<Message>& defaultDiagParams, const ::std::string& diagNamespace,
303  const ::std::string& topic, uint32_t queue_size,
304  const boost::function<void(const ::boost::shared_ptr<Message>&)>& cb, ::ros::TransportHints hints = {})
305  {
306  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>(new ::cras::DiagnosedSubscriber<Message>(
307  *this, this->getDiagParams(diagNamespace, topic), defaultDiagParams, topic, queue_size, cb, hints));
308  result->attach(updater);
309  return ::std::move(result);
310  }
311 
325  template <typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
326  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>>
328  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<C>>& defaultDiagParams, const ::std::string& diagNamespace,
329  const ::std::string& topic, uint32_t queue_size,
330  const boost::function<void(C)>& cb, ::ros::VoidConstPtr obj = {}, ::ros::TransportHints hints = {})
331  {
332  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>>(
333  new ::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>(
334  *this, this->getDiagParams(diagNamespace, topic), defaultDiagParams, topic, queue_size, cb, obj, hints));
335  result->attach(updater);
336  return ::std::move(result);
337  }
338 
353  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
354  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
356  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>& defaultDiagParams, const ::std::string& diagNamespace,
357  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M), T* obj, ::ros::TransportHints hints = {})
358  {
359  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>(
360  new ::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>(
361  *this, this->getDiagParams(diagNamespace, topic), defaultDiagParams, topic, queue_size, cb, obj, hints));
362  result->attach(updater);
363  return ::std::move(result);
364  }
365 
380  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
381  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
383  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>& defaultDiagParams, const ::std::string& diagNamespace,
384  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M) const, T* obj, ::ros::TransportHints hints = {})
385  {
386  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>(
387  new ::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>(
388  *this, this->getDiagParams(diagNamespace, topic), defaultDiagParams, topic, queue_size, cb, obj, hints));
389  result->attach(updater);
390  return ::std::move(result);
391  }
392 
407  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
408  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
410  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>& defaultDiagParams, const ::std::string& diagNamespace,
411  const ::std::string& topic, uint32_t queue_size,
412  void(T::*cb)(M), const ::boost::shared_ptr<T>& obj, ::ros::TransportHints hints = {})
413  {
414  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>(
415  new ::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>(
416  *this, this->getDiagParams(diagNamespace, topic), defaultDiagParams, topic, queue_size, cb, obj, hints));
417  result->attach(updater);
418  return ::std::move(result);
419  }
420 
435  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
436  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
438  const ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>& defaultDiagParams, const ::std::string& diagNamespace,
439  const ::std::string& topic, uint32_t queue_size,
440  void(T::*cb)(M) const, const ::boost::shared_ptr<T>& obj, ::ros::TransportHints hints = {})
441  {
442  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>(
443  new ::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>(
444  *this, this->getDiagParams(diagNamespace, topic), defaultDiagParams, topic, queue_size, cb, obj, hints));
445  result->attach(updater);
446  return ::std::move(result);
447  }
448 
458  template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
459  ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>
461  const ::cras::SimpleTopicStatusParam<Message>& defaultDiagParams, const ::std::string& diagNamespace,
462  ::ros::SubscribeOptions& options)
463  {
464  auto result = ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>(new ::cras::DiagnosedSubscriber<Message>(
465  *this, this->getDiagParams(diagNamespace, options.topic), defaultDiagParams, options));
466  result->attach(updater);
467  return ::std::move(result);
468  }
469 
481  template <typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
482  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
483  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
484  const ::std::string& topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints = {})
485  {
486  return this->template subscribeDiagnosed<M>(updater, ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>(),
487  diagNamespace, topic, queue_size, cb, hints);
488  }
489 
501  template <typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
502  ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>
503  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
504  const ::std::string& topic, uint32_t queue_size,
505  const boost::function<void(const ::boost::shared_ptr<Message>&)>& cb, ::ros::TransportHints hints = {})
506  {
507  return this->template subscribeDiagnosed<Message>(updater, ::cras::SimpleTopicStatusParam<Message>(), diagNamespace,
508  topic, queue_size, cb, hints);
509  }
510 
523  template <typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
524  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>>
525  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
526  const ::std::string& topic, uint32_t queue_size,
527  const boost::function<void(C)>& cb, ::ros::VoidConstPtr obj = {}, ::ros::TransportHints hints = {})
528  {
529  return this->template subscribeDiagnosed<C>(updater, ::cras::SimpleTopicStatusParam<::cras::BaseMessage<C>>(),
530  diagNamespace, topic, queue_size, cb, obj, hints);
531  }
532 
546  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
547  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
548  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
549  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M), T* obj, ::ros::TransportHints hints = {})
550  {
551  return this->template subscribeDiagnosed<M>(updater, ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>(),
552  diagNamespace, topic, queue_size, cb, obj, hints);
553  }
554 
568  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
569  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
570  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
571  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M) const, T* obj, ::ros::TransportHints hints = {})
572  {
573  return this->template subscribeDiagnosed<M>(updater, ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>(),
574  diagNamespace, topic, queue_size, cb, obj, hints);
575  }
576 
590  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
591  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
592  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
593  const ::std::string& topic, uint32_t queue_size,
594  void(T::*cb)(M), const ::boost::shared_ptr<T>& obj, ::ros::TransportHints hints = {})
595  {
596  return this->template subscribeDiagnosed<M>(updater, ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>(),
597  diagNamespace, topic, queue_size, cb, obj, hints);
598  }
599 
613  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
614  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
615  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
616  const ::std::string& topic, uint32_t queue_size,
617  void(T::*cb)(M) const, const ::boost::shared_ptr<T>& obj, ::ros::TransportHints hints = {})
618  {
619  return this->template subscribeDiagnosed<M>(updater, ::cras::SimpleTopicStatusParam<::cras::BaseMessage<M>>(),
620  diagNamespace, topic, queue_size, cb, obj, hints);
621  }
622 
631  template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
632  ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>
633  subscribeDiagnosed(::diagnostic_updater::Updater& updater, const ::std::string& diagNamespace,
634  ::ros::SubscribeOptions& options)
635  {
636  return this->template subscribeDiagnosed<Message>(updater, ::cras::SimpleTopicStatusParam<Message>(),
637  diagNamespace, options);
638  }
639 
651  template <typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
652  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
654  const ::std::string& topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints = {})
655  {
656  return this->template subscribeDiagnosed<M>(updater, "", topic, queue_size, cb, hints);
657  }
658 
670  template <typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
671  ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>
673  const ::std::string& topic, uint32_t queue_size,
674  const boost::function<void(const ::boost::shared_ptr<Message>&)>& cb, ::ros::TransportHints hints = {})
675  {
676  return this->template subscribeDiagnosed<Message>(updater, "", topic, queue_size, cb, hints);
677  }
678 
690  template <typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
691  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>>
693  const ::std::string& topic, uint32_t queue_size,
694  const boost::function<void(C)>& cb, ::ros::VoidConstPtr obj = {}, ::ros::TransportHints hints = {})
695  {
696  return this->template subscribeDiagnosed<C>(updater, "", topic, queue_size, cb, obj, hints);
697  }
698 
712  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
713  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
715  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M), T* obj, ::ros::TransportHints hints = {})
716  {
717  return this->template subscribeDiagnosed<M>(updater, "", topic, queue_size, cb, obj, hints);
718  }
719 
733  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
734  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
736  const ::std::string& topic, uint32_t queue_size, void(T::*cb)(M) const, T* obj, ::ros::TransportHints hints = {})
737  {
738  return this->template subscribeDiagnosed<M>(updater, "", topic, queue_size, cb, obj, hints);
739  }
740 
754  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
755  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
757  const ::std::string& topic, uint32_t queue_size,
758  void(T::*cb)(M), const ::boost::shared_ptr<T>& obj, ::ros::TransportHints hints = {})
759  {
760  return this->template subscribeDiagnosed<M>(updater, "", topic, queue_size, cb, obj, hints);
761  }
762 
776  template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
777  ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>>
779  const ::std::string& topic, uint32_t queue_size,
780  void(T::*cb)(M) const, const ::boost::shared_ptr<T>& obj, ::ros::TransportHints hints = {})
781  {
782  return this->template subscribeDiagnosed<M>(updater, "", topic, queue_size, cb, obj, hints);
783  }
784 
793  template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
794  ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>>
796  {
797  return this->template subscribeDiagnosed<Message>(updater, "", options);
798  }
799 
800 protected:
803 };
804 
805 }
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
datatypes.h
ros::AdvertiseOptions::topic
std::string topic
forwards.h
node_handle.h
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:327
message_utils.hpp
Utilities for working with ROS message files.
boost::shared_ptr< void const >
cras
Definition: any.hpp:15
cras::NodeHandleWithDiagnostics::advertiseDiagnosed
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, const size_t queueSize, const bool latch=false)
Advertise publication of a message, automatically adding diagnostics to it.
Definition: node_handle_with_diagnostics.h:236
cras::BoundParamHelperPtr
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
Definition: bound_param_helper.hpp:24
ros::SubscribeOptions::topic
std::string topic
cras::NodeHandleWithDiagnostics::getDiagParams
virtual ::cras::BoundParamHelperPtr getDiagParams(const ::std::string &diagNs, const ::std::string &topic) const
Get the param helper from which parameters for the diagnostic task can be extracted.
diagnostic_updater::Updater
ros::TransportHints
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:778
bound_param_helper.hpp
Bound param helper (allows omitting the param adapter in each getParam call).
cras::NodeHandleWithDiagnostics
Utils for adding diagnostics to a topic via node handle.
Definition: node_handle_with_diagnostics.h:88
cras::NodeHandleWithDiagnostics::advertiseDiagnosed
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, const size_t queueSize, const bool latch=false)
Advertise publication of a message, automatically adding diagnostics to it.
Definition: node_handle_with_diagnostics.h:198
cras::NodeHandleWithDiagnostics::parentNh
::ros::NodeHandle parentNh
The parent node handle of this one.
Definition: node_handle_with_diagnostics.h:802
cras::NodeHandleWithDiagnostics::advertiseDiagnosed
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
Advertise publication of a message, automatically adding diagnostics to it.
Definition: node_handle_with_diagnostics.h:216
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::AdvertiseOptions
diagnostic_updater.h
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:633
cras::NodeHandleWithDiagnostics::advertiseDiagnosed
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, const size_t queueSize, const bool latch=false)
Advertise publication of a message, automatically adding diagnostics to it.
Definition: node_handle_with_diagnostics.h:150
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:592
transport_hints.h
param_helper.h
Utils for getting node parameters.
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:483
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:735
node.h
Log helper redirecting the logging calls to ROS_ macros.
diagnosed_pub_sub.hpp
ROS message publisher and subscriber with automatic rate and delay diagnostics.
message_traits.h
node_handle.hpp
An adapter that allows getting ROS parameters from a node handle.
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:653
updater
updater
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:525
cras::NodeParamHelper
This mixin allows calling the getParam() helpers.
Definition: param_helper.h:24
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:355
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, ::ros::SubscribeOptions &options)
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:795
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:756
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:382
ros::NodeHandle
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:276
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:615
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:437
cras::NodeHandleWithDiagnostics::prefixDiagNamespace
virtual ::std::string prefixDiagNamespace(const ::std::string &ns) const
Optionally add a private node namespace to the given topic if this nodehandle is in the root node nam...
advertise_options.h
ros::SubscribeOptions
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, const boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:672
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:503
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:714
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:548
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:301
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:460
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, uint32_t queue_size, const boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:692
cras::NodeHandleWithDiagnostics::advertiseDiagnosed
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
Advertise publication of a message, automatically adding diagnostics to it.
Definition: node_handle_with_diagnostics.h:173
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:409
cras::NodeHandleWithDiagnostics::advertiseDiagnosed
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed(::diagnostic_updater::Updater &updater, ::ros::AdvertiseOptions &options)
Advertise publication of a message, automatically adding diagnostics to it.
Definition: node_handle_with_diagnostics.h:253
topic_status_param.hpp
Definitions of parameters for a TopicStatus diagnostic task.
cras::NodeHandleWithDiagnostics::NodeHandleWithDiagnostics
NodeHandleWithDiagnostics(const ::std::string &ns="", const ::ros::M_string &remappings={})
Create the node handle using the passed ROS node handle parameters.
cras::NodeHandleWithDiagnostics::subscribeDiagnosed
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
Subscribe to the given topic, automatically updating the diagnostic task every time a message is rece...
Definition: node_handle_with_diagnostics.h:570
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


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