#include <Manager.h>

Public Member Functions | |
| int | computeBroadcastDest () |
| template<typename Q > | |
| bool | deserialize (char *p, int size, Q &pm) |
| virtual unsigned char | getPriority () |
| virtual void | init_param () |
| virtual bool | isHost () |
| void | justOne () |
| Manager (ros::NodeHandle *n, int port, std::string name, unsigned char priority) | |
| virtual void | run ()=0 |
| template<typename P > | |
| int | serialize (char *p, const boost::shared_ptr< P const > &pm) |
| template<typename P > | |
| int | serialize (char *p, P &pm) |
| void | setBroadcast (bool bc) |
| void | setDecimation (int i) |
| void | setDestination (std::string destination) |
| virtual void | setPriority (unsigned char prio) |
| void | setSource (std::string source) |
| virtual void | start () |
| virtual void | startRX () |
| virtual void | stop () |
Public Attributes | |
| ros::NodeHandle * | n |
Protected Types | |
| enum | wmp_commands_t { STOP, TOPIC_STOP, TOPIC_START, TOPIC_DECIMATE, TOPIC_JUSTONE, SET_PRIORITY, GET_PRIORITY } |
Protected Attributes | |
| bool | amIdst |
| bool | amIsrc |
| bool | amIstatic |
| bool | bc |
| boost::shared_array< uint8_t > | dbuff |
| std::string | decimation |
| std::vector< uint8_t > | dests |
| unsigned char | flow_prio |
| bool | justone |
| std::string | name |
| std::string | param_dest |
| int | port |
| char | sbuff [MAX_DATA_SIZE] |
| bool | stopped |
enum Manager::wmp_commands_t [protected] |
| Manager::Manager | ( | ros::NodeHandle * | n, |
| int | port, | ||
| std::string | name, | ||
| unsigned char | priority | ||
| ) | [inline] |
| int Manager::computeBroadcastDest | ( | ) | [inline] |
| bool Manager::deserialize | ( | char * | p, |
| int | size, | ||
| Q & | pm | ||
| ) | [inline] |
| virtual unsigned char Manager::getPriority | ( | ) | [inline, virtual] |
| virtual void Manager::init_param | ( | ) | [inline, virtual] |
Reimplemented in ServiceManager< T >, and ServiceManager< ros_rt_wmp_msgs::WMPControl >.
| virtual bool Manager::isHost | ( | ) | [inline, virtual] |
Reimplemented in ServiceManager< T >, ServiceManager< ros_rt_wmp_msgs::WMPControl >, and TopicManager< T >.
| void Manager::justOne | ( | ) | [inline] |
| virtual void Manager::run | ( | ) | [pure virtual] |
Implemented in TopicManager< T >, TFManager, ServiceManager< T >, and ServiceManager< ros_rt_wmp_msgs::WMPControl >.
| int Manager::serialize | ( | char * | p, |
| const boost::shared_ptr< P const > & | pm | ||
| ) | [inline] |
| int Manager::serialize | ( | char * | p, |
| P & | pm | ||
| ) | [inline] |
| void Manager::setBroadcast | ( | bool | bc | ) | [inline] |
| void Manager::setDecimation | ( | int | i | ) | [inline] |
| void Manager::setDestination | ( | std::string | destination | ) | [inline] |
| virtual void Manager::setPriority | ( | unsigned char | prio | ) | [inline, virtual] |
| void Manager::setSource | ( | std::string | source | ) | [inline] |
| virtual void Manager::start | ( | ) | [inline, virtual] |
| virtual void Manager::startRX | ( | ) | [inline, virtual] |
Reimplemented in TFManager, TopicManager< T >, ServiceManager< T >, and ServiceManager< ros_rt_wmp_msgs::WMPControl >.
| virtual void Manager::stop | ( | ) | [inline, virtual] |
bool Manager::amIdst [protected] |
bool Manager::amIsrc [protected] |
bool Manager::amIstatic [protected] |
bool Manager::bc [protected] |
boost::shared_array<uint8_t> Manager::dbuff [protected] |
std::string Manager::decimation [protected] |
std::vector<uint8_t> Manager::dests [protected] |
unsigned char Manager::flow_prio [protected] |
bool Manager::justone [protected] |
std::string Manager::name [protected] |
std::string Manager::param_dest [protected] |
int Manager::port [protected] |
char Manager::sbuff[MAX_DATA_SIZE] [protected] |
bool Manager::stopped [protected] |