#include <topic_handle.h>

| Public Types | |
| typedef int | priority_type | 
| Public Member Functions | |
| const T & | getMessage () const | 
| const std::string & | getName () const | 
| const priority_type & | getPriority () const | 
| getPriority Priority getter | |
| const T & | getStamp () const | 
| const double & | getTimeout () const | 
| const std::string & | getTopic () const | 
| bool | hasExpired () const | 
| hasExpired | |
| TopicHandle_ (ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux) | |
| TopicHandle_. | |
| virtual | ~TopicHandle_ () | 
| Protected Attributes | |
| T | msg_ | 
| TwistMux * | mux_ | 
| std::string | name_ | 
| ros::NodeHandle | nh_ | 
| priority_type | priority_ | 
| ros::Time | stamp_ | 
| ros::Subscriber | subscriber_ | 
| double | timeout_ | 
| std::string | topic_ | 
Definition at line 42 of file topic_handle.h.
| typedef int twist_mux::TopicHandle_< T >::priority_type | 
Reimplemented in twist_mux::LockTopicHandle, and twist_mux::VelocityTopicHandle.
Definition at line 46 of file topic_handle.h.
| twist_mux::TopicHandle_< T >::TopicHandle_ | ( | ros::NodeHandle & | nh, | 
| const std::string & | name, | ||
| const std::string & | topic, | ||
| double | timeout, | ||
| priority_type | priority, | ||
| TwistMux * | mux | ||
| ) |  [inline] | 
| nh | Node handle | 
| name | Name identifier | 
| topic | Topic name | 
| timeout | Timeout to consider that the messages are old; note that initially the message stamp is set to 0.0, so the message has expired | 
| priority | Priority of the topic | 
Definition at line 58 of file topic_handle.h.
| virtual twist_mux::TopicHandle_< T >::~TopicHandle_ | ( | ) |  [inline, virtual] | 
Definition at line 75 of file topic_handle.h.
| const T& twist_mux::TopicHandle_< T >::getMessage | ( | ) | const  [inline] | 
Definition at line 121 of file topic_handle.h.
| const std::string& twist_mux::TopicHandle_< T >::getName | ( | ) | const  [inline] | 
Definition at line 92 of file topic_handle.h.
| const priority_type& twist_mux::TopicHandle_< T >::getPriority | ( | ) | const  [inline] | 
| const T& twist_mux::TopicHandle_< T >::getStamp | ( | ) | const  [inline] | 
Definition at line 116 of file topic_handle.h.
| const double& twist_mux::TopicHandle_< T >::getTimeout | ( | ) | const  [inline] | 
Definition at line 102 of file topic_handle.h.
| const std::string& twist_mux::TopicHandle_< T >::getTopic | ( | ) | const  [inline] | 
Definition at line 97 of file topic_handle.h.
| bool twist_mux::TopicHandle_< T >::hasExpired | ( | ) | const  [inline] | 
hasExpired
Definition at line 86 of file topic_handle.h.
| T twist_mux::TopicHandle_< T >::msg_  [protected] | 
Definition at line 139 of file topic_handle.h.
| TwistMux* twist_mux::TopicHandle_< T >::mux_  [protected] | 
Definition at line 136 of file topic_handle.h.
| std::string twist_mux::TopicHandle_< T >::name_  [protected] | 
Definition at line 129 of file topic_handle.h.
| ros::NodeHandle twist_mux::TopicHandle_< T >::nh_  [protected] | 
Definition at line 127 of file topic_handle.h.
| priority_type twist_mux::TopicHandle_< T >::priority_  [protected] | 
Definition at line 133 of file topic_handle.h.
| ros::Time twist_mux::TopicHandle_< T >::stamp_  [protected] | 
Definition at line 138 of file topic_handle.h.
| ros::Subscriber twist_mux::TopicHandle_< T >::subscriber_  [protected] | 
Definition at line 131 of file topic_handle.h.
| double twist_mux::TopicHandle_< T >::timeout_  [protected] | 
Definition at line 132 of file topic_handle.h.
| std::string twist_mux::TopicHandle_< T >::topic_  [protected] | 
Definition at line 130 of file topic_handle.h.