#include <subscriber_impl.h>

| Public Member Functions | |
| template<class M2 > | |
| boost::enable_if< ros::message_traits::HasHeader< M2 >, void >::type | handleMessage (const boost::shared_ptr< M const > &msg) | 
| template<class M2 > | |
| boost::disable_if< ros::message_traits::HasHeader< M2 >, void >::type | handleMessage (const boost::shared_ptr< M const > &msg) | 
| StorageSubscriberImpl (ros::NodeHandle &nh, const std::string &topic, boost::shared_ptr< M const > *dest, const ros::TransportHints &transport_hints) | |
|  Public Member Functions inherited from swri::SubscriberImpl | |
| ros::Duration | age (const ros::Time &now) const | 
| bool | blockTimeouts (bool block) | 
| bool | inTimeout () | 
| const std::string & | mappedTopic () const | 
| ros::Duration | maxLatency () const | 
| ros::Duration | maxPeriod () const | 
| double | meanFrequencyHz () const | 
| ros::Duration | meanLatency () const | 
| ros::Duration | meanPeriod () const | 
| int | messageCount () const | 
| ros::Duration | minLatency () const | 
| ros::Duration | minPeriod () const | 
| int | numPublishers () const | 
| void | resetStatistics () | 
| void | setTimeout (const ros::Duration &time_out) | 
| SubscriberImpl () | |
| ros::Duration | timeout () const | 
| int | timeoutCount () | 
| bool | timeoutEnabled () const | 
| bool | timeoutsBlocked () const | 
| const std::string & | unmappedTopic () const | 
| Private Attributes | |
| boost::shared_ptr< M const > * | dest_ | 
| Additional Inherited Members | |
|  Protected Member Functions inherited from swri::SubscriberImpl | |
| void | checkTimeout (const ros::Time &now) | 
| void | processHeader (const ros::Time &stamp) | 
|  Protected Attributes inherited from swri::SubscriberImpl | |
| bool | blocking_timeout_ | 
| bool | in_timeout_ | 
| ros::Time | last_header_stamp_ | 
| ros::Time | last_receive_time_ | 
| std::string | mapped_topic_ | 
| ros::Duration | max_latency_ | 
| ros::Duration | max_period_ | 
| int | message_count_ | 
| ros::Duration | min_latency_ | 
| ros::Duration | min_period_ | 
| ros::Subscriber | sub_ | 
| ros::Duration | timeout_ | 
| int | timeout_count_ | 
| ros::Duration | total_latency_ | 
| ros::Duration | total_periods_ | 
| std::string | unmapped_topic_ | 
Definition at line 402 of file subscriber_impl.h.
| 
 | inline | 
Definition at line 407 of file subscriber_impl.h.
| 
 | inline | 
Definition at line 435 of file subscriber_impl.h.
| 
 | inline | 
Definition at line 444 of file subscriber_impl.h.
| 
 | private | 
Definition at line 404 of file subscriber_impl.h.