#include <TopicManager.h>

Public Member Functions | |
| virtual void | callback (const boost::shared_ptr< T const > &message) |
| virtual void | fillDestination (const boost::shared_ptr< T const > &message) |
| virtual int | getPriority (const boost::shared_ptr< T const > &message) |
| virtual int | getSubPort (T &pm) |
| virtual std::string | getSubTopic (T &pm) |
| void | init () |
| virtual bool | isHost () |
| virtual bool | popMessage (T &pm, unsigned int &size, unsigned char &src1, signed char &pri) |
| virtual void | run () |
| bool | shouldDecimate () |
| virtual void | startRX () |
| TopicManager (ros::NodeHandle *n, int port, std::string name, std::string source, std::string destination, unsigned char priority, bool broadcast) | |
| TopicManager (ros::NodeHandle *n, int port, std::string name, std::string source, unsigned char priority, bool broadcast) | |
Protected Attributes | |
| int | counter |
| std::map< std::string, info_t > | flows_map |
| ros::Subscriber | sub |
Definition at line 45 of file TopicManager.h.
| TopicManager< T >::TopicManager | ( | ros::NodeHandle * | n, |
| int | port, | ||
| std::string | name, | ||
| std::string | source, | ||
| std::string | destination, | ||
| unsigned char | priority, | ||
| bool | broadcast | ||
| ) | [inline] |
Definition at line 53 of file TopicManager.h.
| TopicManager< T >::TopicManager | ( | ros::NodeHandle * | n, |
| int | port, | ||
| std::string | name, | ||
| std::string | source, | ||
| unsigned char | priority, | ||
| bool | broadcast | ||
| ) | [inline] |
Definition at line 63 of file TopicManager.h.
| virtual void TopicManager< T >::callback | ( | const boost::shared_ptr< T const > & | message | ) | [inline, virtual] |
Definition at line 137 of file TopicManager.h.
| virtual void TopicManager< T >::fillDestination | ( | const boost::shared_ptr< T const > & | message | ) | [inline, virtual] |
Reimplemented in WMPTopicManager< T >.
Definition at line 120 of file TopicManager.h.
| virtual int TopicManager< T >::getPriority | ( | const boost::shared_ptr< T const > & | message | ) | [inline, virtual] |
Reimplemented in WMPTopicManager< T >.
Definition at line 127 of file TopicManager.h.
| virtual int TopicManager< T >::getSubPort | ( | T & | pm | ) | [inline, virtual] |
Definition at line 131 of file TopicManager.h.
| virtual std::string TopicManager< T >::getSubTopic | ( | T & | pm | ) | [inline, virtual] |
Reimplemented in WMPTopicManager< T >.
Definition at line 134 of file TopicManager.h.
| void TopicManager< T >::init | ( | ) | [inline] |
Definition at line 84 of file TopicManager.h.
| virtual bool TopicManager< T >::isHost | ( | ) | [inline, virtual] |
Reimplemented from Manager.
Definition at line 79 of file TopicManager.h.
| virtual bool TopicManager< T >::popMessage | ( | T & | pm, |
| unsigned int & | size, | ||
| unsigned char & | src1, | ||
| signed char & | pri | ||
| ) | [inline, virtual] |
Definition at line 174 of file TopicManager.h.
| virtual void TopicManager< T >::run | ( | ) | [inline, virtual] |
Implements Manager.
Definition at line 187 of file TopicManager.h.
| bool TopicManager< T >::shouldDecimate | ( | ) | [inline] |
Definition at line 104 of file TopicManager.h.
| virtual void TopicManager< T >::startRX | ( | ) | [inline, virtual] |
Reimplemented from Manager.
Definition at line 71 of file TopicManager.h.
int TopicManager< T >::counter [protected] |
Definition at line 49 of file TopicManager.h.
std::map<std::string, info_t> TopicManager< T >::flows_map [protected] |
Definition at line 47 of file TopicManager.h.
ros::Subscriber TopicManager< T >::sub [protected] |
Definition at line 48 of file TopicManager.h.