#include <latched_subscriber.h>
Classes | |
struct | LatchedReceiver |
Public Member Functions | |
const boost::shared_ptr< M const > & | data () const |
void | initialize (ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints()) |
LatchedSubscriber () | |
LatchedSubscriber (ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints()) | |
M const * | operator-> () const |
LatchedSubscriber< M > & | operator= (const LatchedSubscriber< M > &other) |
void | reset () |
![]() | |
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 |
virtual | ~Subscriber () |
Private Attributes | |
M | empty_ |
boost::shared_ptr< LatchedReceiver< M > > | receiver_ |
Additional Inherited Members | |
![]() | |
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 } |
Definition at line 25 of file latched_subscriber.h.
swri::LatchedSubscriber< M >::LatchedSubscriber | ( | ) |
Definition at line 71 of file latched_subscriber.h.
swri::LatchedSubscriber< M >::LatchedSubscriber | ( | ros::NodeHandle & | nh, |
const std::string & | topic, | ||
const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
) |
Definition at line 79 of file latched_subscriber.h.
const boost::shared_ptr< M const > & swri::LatchedSubscriber< M >::data | ( | ) | const |
Definition at line 111 of file latched_subscriber.h.
void swri::LatchedSubscriber< M >::initialize | ( | ros::NodeHandle & | nh, |
const std::string & | topic, | ||
const ros::TransportHints & | transport_hints = ros::TransportHints() |
||
) |
Definition at line 93 of file latched_subscriber.h.
M const * swri::LatchedSubscriber< M >::operator-> | ( | ) | const |
Definition at line 117 of file latched_subscriber.h.
LatchedSubscriber< M > & swri::LatchedSubscriber< M >::operator= | ( | const LatchedSubscriber< M > & | other | ) |
Definition at line 103 of file latched_subscriber.h.
void swri::LatchedSubscriber< M >::reset | ( | ) |
Definition at line 127 of file latched_subscriber.h.
|
private |
Definition at line 38 of file latched_subscriber.h.
|
private |
Definition at line 37 of file latched_subscriber.h.