Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes
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, 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 initNode (char *portName)
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 SubscriberT >
bool subscribe (SubscriberT &s)
void syncTime (uint8_t *data)

Protected Attributes

int bytes_
int checksum_
bool configured_
Hardware hardware_
int index_
uint32_t last_msg_timeout_time
uint32_t last_sync_receive_time
uint32_t last_sync_time
uint8_t message_in [INPUT_SIZE]
uint8_t message_out [OUTPUT_SIZE]
int mode_
uint32_t nsec_offset
Publisherpublishers [MAX_PUBLISHERS]
uint32_t rt_time
uint32_t 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 98 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 119 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 337 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 365 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 286 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 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>
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 506 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 517 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 528 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 146 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 155 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 460 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 468 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 477 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 480 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 471 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 474 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 391 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 314 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 422 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 492 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 294 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 379 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 324 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 184 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 SubscriberT >
bool ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::subscribe ( SubscriberT &  s) [inline]

Definition at line 352 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 ( uint8_t *  data) [inline]

Definition at line 301 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 166 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 169 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 171 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 101 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 168 of file node_handle.h.

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

Definition at line 176 of file node_handle.h.

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

Definition at line 175 of file node_handle.h.

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

Definition at line 174 of file node_handle.h.

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

Definition at line 109 of file node_handle.h.

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

Definition at line 110 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 161 of file node_handle.h.

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

Definition at line 107 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 489 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 112 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 490 of file node_handle.h.

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

Definition at line 104 of file node_handle.h.

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

Definition at line 107 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 113 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 167 of file node_handle.h.


The documentation for this class was generated from the following file:


rosserial_client
Author(s): Michael Ferguson, Adam Stambler
autogenerated on Thu Jun 6 2019 19:56:25