#include <node_handle.h>
Public Member Functions | |
| bool | advertise (Publisher &p) | 
| template<typename SrvReq , typename SrvResp > | |
| bool | advertiseService (ServiceServer< SrvReq, SrvResp > &srv) | 
| bool | connected () | 
| Hardware * | getHardware () | 
| bool | getParam (const char *name, int *param, int length=1) | 
| bool | getParam (const char *name, float *param, int length=1) | 
| bool | getParam (const char *name, char **param, int length=1) | 
| void | initNode () | 
| void | logdebug (const char *msg) | 
| void | logerror (const char *msg) | 
| void | logfatal (const char *msg) | 
| void | loginfo (const char *msg) | 
| void | logwarn (const char *msg) | 
| void | negotiateTopics () | 
| NodeHandle_ () | |
| Time | now () | 
| void | requestSyncTime () | 
| void | setNow (Time &new_now) | 
| virtual void | spinOnce () | 
| template<typename MsgT > | |
| bool | subscribe (Subscriber< MsgT > &s) | 
| void | syncTime (unsigned char *data) | 
Protected Member Functions | |
| bool | registerReceiver (MsgReceiver *rcv) | 
Protected Attributes | |
| int | bytes_ | 
| int | checksum_ | 
| Hardware | hardware_ | 
| int | index_ | 
| unsigned long | last_msg_timeout_time | 
| unsigned long | last_sync_receive_time | 
| unsigned long | last_sync_time | 
| unsigned char | message_in [INPUT_SIZE] | 
| int | mode_ | 
| NodeOutput< Hardware, OUTPUT_SIZE > | no_ | 
| unsigned long | nsec_offset | 
| Publisher * | publishers [MAX_PUBLISHERS] | 
| MsgReceiver * | receivers [MAX_SUBSCRIBERS] | 
| unsigned long | rt_time | 
| unsigned long | sec_offset | 
| int | topic_ | 
| int | total_receivers | 
Private Member Functions | |
| void | log (char byte, const char *msg) | 
| bool | requestParam (const char *name, int time_out=1000) | 
Private Attributes | |
| bool | param_recieved | 
| rosserial_msgs::RequestParamResponse | req_param_resp | 
Definition at line 74 of file node_handle.h.
| ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::NodeHandle_ | ( | ) |  [inline] | 
        
Definition at line 95 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::advertise | ( | Publisher & | p | ) |  [inline] | 
        
Definition at line 273 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::advertiseService | ( | ServiceServer< SrvReq, SrvResp > & | srv | ) |  [inline] | 
        
Definition at line 296 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::connected | ( | ) |  [inline] | 
        
Definition at line 223 of file node_handle.h.
| Hardware* ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::getHardware | ( | ) |  [inline] | 
        
Definition at line 97 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::getParam | ( | const char * | name, | 
| int * | param, | ||
| int | length = 1  | 
        ||
| ) |  [inline] | 
        
Definition at line 381 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::getParam | ( | const char * | name, | 
| float * | param, | ||
| int | length = 1  | 
        ||
| ) |  [inline] | 
        
Definition at line 392 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::getParam | ( | const char * | name, | 
| char ** | param, | ||
| int | length = 1  | 
        ||
| ) |  [inline] | 
        
Definition at line 403 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::initNode | ( | ) |  [inline] | 
        
Definition at line 102 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::log | ( | char | byte, | 
| const char * | msg | ||
| ) |  [inline, private] | 
        
Definition at line 334 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logdebug | ( | const char * | msg | ) |  [inline] | 
        
Definition at line 342 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logerror | ( | const char * | msg | ) |  [inline] | 
        
Definition at line 351 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logfatal | ( | const char * | msg | ) |  [inline] | 
        
Definition at line 354 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::loginfo | ( | const char * | msg | ) |  [inline] | 
        
Definition at line 345 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logwarn | ( | const char * | msg | ) |  [inline] | 
        
Definition at line 348 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::negotiateTopics | ( | ) |  [inline] | 
        
Definition at line 301 of file node_handle.h.
| Time ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::now | ( | ) |  [inline] | 
        
Definition at line 252 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::registerReceiver | ( | MsgReceiver * | rcv | ) |  [inline, protected] | 
        
Definition at line 126 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::requestParam | ( | const char * | name, | 
| int | time_out = 1000  | 
        ||
| ) |  [inline, private] | 
        
Definition at line 367 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::requestSyncTime | ( | ) |  [inline] | 
        
Definition at line 231 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::setNow | ( | Time & | new_now | ) |  [inline] | 
        
Definition at line 261 of file node_handle.h.
| virtual void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::spinOnce | ( | ) |  [inline, virtual] | 
        
Definition at line 140 of file node_handle.h.
| bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::subscribe | ( | Subscriber< MsgT > & | s | ) |  [inline] | 
        
Definition at line 291 of file node_handle.h.
| void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::syncTime | ( | unsigned char * | data | ) |  [inline] | 
        
Definition at line 238 of file node_handle.h.
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::bytes_ [protected] | 
        
Definition at line 114 of file node_handle.h.
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::checksum_ [protected] | 
        
Definition at line 117 of file node_handle.h.
Hardware ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::hardware_ [protected] | 
        
Definition at line 77 of file node_handle.h.
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::index_ [protected] | 
        
Definition at line 116 of file node_handle.h.
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::last_msg_timeout_time [protected] | 
        
Definition at line 124 of file node_handle.h.
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::last_sync_receive_time [protected] | 
        
Definition at line 123 of file node_handle.h.
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::last_sync_time [protected] | 
        
Definition at line 122 of file node_handle.h.
unsigned char ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::message_in[INPUT_SIZE] [protected] | 
        
Definition at line 86 of file node_handle.h.
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::mode_ [protected] | 
        
Definition at line 109 of file node_handle.h.
NodeOutput<Hardware, OUTPUT_SIZE> ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::no_ [protected] | 
        
Definition at line 78 of file node_handle.h.
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::nsec_offset [protected] | 
        
Definition at line 84 of file node_handle.h.
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::param_recieved [private] | 
        
Definition at line 364 of file node_handle.h.
Publisher* ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::publishers[MAX_PUBLISHERS] [protected] | 
        
Definition at line 88 of file node_handle.h.
MsgReceiver* ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::receivers[MAX_SUBSCRIBERS] [protected] | 
        
Definition at line 89 of file node_handle.h.
rosserial_msgs::RequestParamResponse ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::req_param_resp [private] | 
        
Definition at line 365 of file node_handle.h.
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::rt_time [protected] | 
        
Definition at line 81 of file node_handle.h.
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::sec_offset [protected] | 
        
Definition at line 84 of file node_handle.h.
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::topic_ [protected] | 
        
Definition at line 115 of file node_handle.h.
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::total_receivers [protected] | 
        
Definition at line 119 of file node_handle.h.