#include <subscriber.h>

Public Types | |
| enum | DIAGNOSTIC_FLAGS { DIAG_CONNECTION = 1 << 0, DIAG_MSG_COUNT = 1 << 1, DIAG_TIMEOUT = 1 << 2, DIAG_LATENCY = 1 << 3, DIAG_RATE = 1 << 4, DIAG_ALL = ~0, DIAG_MOST = DIAG_ALL ^ DIAG_CONNECTION } |
Public Member Functions | |
| ros::Duration | age (const ros::Time &now=ros::TIME_MIN) const |
| double | ageMilliseconds (const ros::Time &now=ros::TIME_MIN) const |
| double | ageSeconds (const ros::Time &now=ros::TIME_MIN) const |
| void | appendDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags) |
| bool | blockTimeouts (bool block) |
| bool | inTimeout () |
| const std::string & | mappedTopic () const |
| ros::Duration | maxLatency () const |
| double | maxLatencyMicroseconds () const |
| ros::Duration | maxPeriod () const |
| double | maxPeriodMilliseconds () const |
| double | meanFrequencyHz () const |
| ros::Duration | meanLatency () const |
| double | meanLatencyMicroseconds () const |
| ros::Duration | meanPeriod () const |
| double | meanPeriodMilliseconds () const |
| int | messageCount () const |
| ros::Duration | minLatency () const |
| double | minLatencyMicroseconds () const |
| ros::Duration | minPeriod () const |
| double | minPeriodMilliseconds () const |
| int | numPublishers () const |
| Subscriber & | operator= (const Subscriber &other) |
| void | resetStatistics () |
| void | setTimeout (const ros::Duration &time_out) |
| void | setTimeout (const double time_out) |
| Subscriber () | |
| template<class M , class T > | |
| Subscriber (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const ros::TransportHints &transport_hints=ros::TransportHints()) | |
| template<class M > | |
| Subscriber (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::TransportHints &transport_hints=ros::TransportHints()) | |
| template<class M > | |
| Subscriber (ros::NodeHandle &nh, const std::string &topic, boost::shared_ptr< M const > *dest, const ros::TransportHints &transport_hints=ros::TransportHints()) | |
| ros::Duration | timeout () const |
| int | timeoutCount () |
| bool | timeoutEnabled () const |
| double | timeoutMilliseconds () const |
| void | timeoutParam (const ros::NodeHandle &nh, const std::string ¶meter_name, const double default_value) |
| bool | timeoutsBlocked () const |
| const std::string & | unmappedTopic () const |
Private Attributes | |
| boost::shared_ptr< SubscriberImpl > | impl_ |
Definition at line 61 of file subscriber.h.
Definition at line 177 of file subscriber.h.
| swri::Subscriber::Subscriber | ( | ) | [inline] |
Definition at line 205 of file subscriber.h.
| swri::Subscriber::Subscriber | ( | ros::NodeHandle & | nh, |
| const std::string & | topic, | ||
| uint32_t | queue_size, | ||
| void(T::*)(const boost::shared_ptr< M const > &) | fp, | ||
| T * | obj, | ||
| const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
| ) | [inline] |
Definition at line 214 of file subscriber.h.
| swri::Subscriber::Subscriber | ( | ros::NodeHandle & | nh, |
| const std::string & | topic, | ||
| uint32_t | queue_size, | ||
| const boost::function< void(const boost::shared_ptr< M const > &)> & | callback, | ||
| const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
| ) | [inline] |
Definition at line 228 of file subscriber.h.
| swri::Subscriber::Subscriber | ( | ros::NodeHandle & | nh, |
| const std::string & | topic, | ||
| boost::shared_ptr< M const > * | dest, | ||
| const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
| ) | [inline] |
Definition at line 241 of file subscriber.h.
| ros::Duration swri::Subscriber::age | ( | const ros::Time & | now = ros::TIME_MIN | ) | const [inline] |
Definition at line 308 of file subscriber.h.
| double swri::Subscriber::ageMilliseconds | ( | const ros::Time & | now = ros::TIME_MIN | ) | const [inline] |
Definition at line 324 of file subscriber.h.
| double swri::Subscriber::ageSeconds | ( | const ros::Time & | now = ros::TIME_MIN | ) | const [inline] |
Definition at line 318 of file subscriber.h.
| void swri::Subscriber::appendDiagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | status, |
| const std::string & | name, | ||
| const int | flags | ||
| ) | [inline] |
Definition at line 473 of file subscriber.h.
| bool swri::Subscriber::blockTimeouts | ( | bool | block | ) | [inline] |
Definition at line 431 of file subscriber.h.
| bool swri::Subscriber::inTimeout | ( | ) | [inline] |
Definition at line 461 of file subscriber.h.
| const std::string & swri::Subscriber::mappedTopic | ( | ) | const [inline] |
Definition at line 284 of file subscriber.h.
| ros::Duration swri::Subscriber::maxLatency | ( | ) | const [inline] |
Definition at line 342 of file subscriber.h.
| double swri::Subscriber::maxLatencyMicroseconds | ( | ) | const [inline] |
Definition at line 360 of file subscriber.h.
| ros::Duration swri::Subscriber::maxPeriod | ( | ) | const [inline] |
Definition at line 384 of file subscriber.h.
| double swri::Subscriber::maxPeriodMilliseconds | ( | ) | const [inline] |
Definition at line 402 of file subscriber.h.
| double swri::Subscriber::meanFrequencyHz | ( | ) | const [inline] |
Definition at line 372 of file subscriber.h.
| ros::Duration swri::Subscriber::meanLatency | ( | ) | const [inline] |
Definition at line 330 of file subscriber.h.
| double swri::Subscriber::meanLatencyMicroseconds | ( | ) | const [inline] |
Definition at line 348 of file subscriber.h.
| ros::Duration swri::Subscriber::meanPeriod | ( | ) | const [inline] |
Definition at line 366 of file subscriber.h.
| double swri::Subscriber::meanPeriodMilliseconds | ( | ) | const [inline] |
Definition at line 390 of file subscriber.h.
| int swri::Subscriber::messageCount | ( | ) | const [inline] |
Definition at line 302 of file subscriber.h.
| ros::Duration swri::Subscriber::minLatency | ( | ) | const [inline] |
Definition at line 336 of file subscriber.h.
| double swri::Subscriber::minLatencyMicroseconds | ( | ) | const [inline] |
Definition at line 354 of file subscriber.h.
| ros::Duration swri::Subscriber::minPeriod | ( | ) | const [inline] |
Definition at line 378 of file subscriber.h.
| double swri::Subscriber::minPeriodMilliseconds | ( | ) | const [inline] |
Definition at line 396 of file subscriber.h.
| int swri::Subscriber::numPublishers | ( | ) | const [inline] |
Definition at line 290 of file subscriber.h.
| Subscriber & swri::Subscriber::operator= | ( | const Subscriber & | other | ) | [inline] |
Definition at line 252 of file subscriber.h.
| void swri::Subscriber::resetStatistics | ( | ) | [inline] |
Definition at line 296 of file subscriber.h.
| void swri::Subscriber::setTimeout | ( | const ros::Duration & | time_out | ) | [inline] |
Definition at line 408 of file subscriber.h.
| void swri::Subscriber::setTimeout | ( | const double | time_out | ) | [inline] |
Definition at line 414 of file subscriber.h.
| ros::Duration swri::Subscriber::timeout | ( | ) | const [inline] |
Definition at line 443 of file subscriber.h.
| int swri::Subscriber::timeoutCount | ( | ) | [inline] |
Definition at line 467 of file subscriber.h.
| bool swri::Subscriber::timeoutEnabled | ( | ) | const [inline] |
Definition at line 449 of file subscriber.h.
| double swri::Subscriber::timeoutMilliseconds | ( | ) | const [inline] |
Definition at line 455 of file subscriber.h.
| void swri::Subscriber::timeoutParam | ( | const ros::NodeHandle & | nh, |
| const std::string & | parameter_name, | ||
| const double | default_value | ||
| ) | [inline] |
Definition at line 420 of file subscriber.h.
| bool swri::Subscriber::timeoutsBlocked | ( | ) | const [inline] |
Definition at line 437 of file subscriber.h.
| const std::string & swri::Subscriber::unmappedTopic | ( | ) | const [inline] |
Definition at line 278 of file subscriber.h.
boost::shared_ptr<SubscriberImpl> swri::Subscriber::impl_ [private] |
Definition at line 69 of file subscriber.h.