|  | 
| 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 | 
|  | 
template<class M>
class swri::LatchedSubscriber< M >
Definition at line 25 of file latched_subscriber.h.