$search

ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE > Class Template Reference

#include <node_handle.h>

Inheritance diagram for ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool advertise (Publisher &p)
template<typename MReq , typename MRes >
bool advertiseService (ServiceServer< MReq, MRes > &srv)
virtual bool connected ()
Hardware * getHardware ()
bool getParam (const char *name, char **param, int length=1)
bool getParam (const char *name, float *param, int length=1)
bool getParam (const char *name, int *param, int length=1)
void initNode (char *portName)
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 ()
virtual int publish (int id, const Msg *msg)
void requestSyncTime ()
template<typename MReq , typename MRes >
bool serviceClient (ServiceClient< MReq, MRes > &srv)
void setNow (Time &new_now)
virtual int spinOnce ()
template<typename MsgT >
bool subscribe (Subscriber< MsgT > &s)
void syncTime (unsigned char *data)

Protected Attributes

int bytes_
int checksum_
bool configured_
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]
unsigned char message_out [OUTPUT_SIZE]
int mode_
unsigned long nsec_offset
Publisherpublishers [MAX_PUBLISHERS]
unsigned long rt_time
unsigned long sec_offset
Subscriber_subscribers [MAX_SUBSCRIBERS]
int topic_

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

Detailed Description

template<class Hardware, int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
class ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >

Definition at line 83 of file node_handle.h.


Constructor & Destructor Documentation

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::NodeHandle_ (  )  [inline]

Definition at line 104 of file node_handle.h.


Member Function Documentation

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::advertise ( Publisher p  )  [inline]

Definition at line 284 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
template<typename MReq , typename MRes >
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::advertiseService ( ServiceServer< MReq, MRes > &  srv  )  [inline]

Definition at line 312 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
virtual bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::connected (  )  [inline, virtual]

Implements ros::NodeHandleBase_.

Definition at line 234 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
Hardware* ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::getHardware (  )  [inline]

Definition at line 106 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
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 472 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
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 461 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
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 450 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::initNode ( char *  portName  )  [inline]

Definition at line 120 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::initNode (  )  [inline]

Definition at line 111 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::log ( char  byte,
const char *  msg 
) [inline, private]

Definition at line 404 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logdebug ( const char *  msg  )  [inline]

Definition at line 412 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logerror ( const char *  msg  )  [inline]

Definition at line 421 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logfatal ( const char *  msg  )  [inline]

Definition at line 424 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::loginfo ( const char *  msg  )  [inline]

Definition at line 415 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::logwarn ( const char *  msg  )  [inline]

Definition at line 418 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::negotiateTopics (  )  [inline]

Definition at line 338 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
Time ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::now (  )  [inline]

Definition at line 262 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
virtual int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::publish ( int  id,
const Msg msg 
) [inline, virtual]

Implements ros::NodeHandleBase_.

Definition at line 369 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
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 436 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::requestSyncTime (  )  [inline]

Definition at line 242 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
template<typename MReq , typename MRes >
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::serviceClient ( ServiceClient< MReq, MRes > &  srv  )  [inline]

Definition at line 326 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::setNow ( Time new_now  )  [inline]

Definition at line 271 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
virtual int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::spinOnce (  )  [inline, virtual]

Implements ros::NodeHandleBase_.

Definition at line 148 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
template<typename MsgT >
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::subscribe ( Subscriber< MsgT > &  s  )  [inline]

Definition at line 299 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
void ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::syncTime ( unsigned char *  data  )  [inline]

Definition at line 249 of file node_handle.h.


Member Data Documentation

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::bytes_ [protected]

Definition at line 131 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::checksum_ [protected]

Definition at line 134 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::configured_ [protected]

Definition at line 136 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
Hardware ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::hardware_ [protected]

Definition at line 86 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::index_ [protected]

Definition at line 133 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::last_msg_timeout_time [protected]

Definition at line 141 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::last_sync_receive_time [protected]

Definition at line 140 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::last_sync_time [protected]

Definition at line 139 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned char ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::message_in[INPUT_SIZE] [protected]

Definition at line 94 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned char ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::message_out[OUTPUT_SIZE] [protected]

Definition at line 95 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::mode_ [protected]

Definition at line 126 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::nsec_offset [protected]

Definition at line 92 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::param_recieved [private]

Definition at line 433 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
Publisher* ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::publishers[MAX_PUBLISHERS] [protected]

Definition at line 97 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
rosserial_msgs::RequestParamResponse ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::req_param_resp [private]

Definition at line 434 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::rt_time [protected]

Definition at line 89 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
unsigned long ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::sec_offset [protected]

Definition at line 92 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
Subscriber_* ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::subscribers[MAX_SUBSCRIBERS] [protected]

Definition at line 98 of file node_handle.h.

template<class Hardware , int MAX_SUBSCRIBERS = 25, int MAX_PUBLISHERS = 25, int INPUT_SIZE = 512, int OUTPUT_SIZE = 512>
int ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::topic_ [protected]

Definition at line 132 of file node_handle.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


rosserial_client
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Sat Mar 2 13:26:04 2013