Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
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]

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 MsgT >
bool subscribe (Subscriber< MsgT > &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 81 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 102 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 320 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 348 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 ( )
inlinevirtual

Implements ros::NodeHandleBase_.

Definition at line 269 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 124 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 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>
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 500 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 511 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 129 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 138 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 
)
inlineprivate

Definition at line 443 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 451 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 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 >::logfatal ( const char *  msg)
inline

Definition at line 463 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 454 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 457 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 374 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 297 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 
)
inlinevirtual

Implements ros::NodeHandleBase_.

Definition at line 405 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 
)
inlineprivate

Definition at line 475 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 277 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 362 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 307 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 ( )
inlinevirtual

Implements ros::NodeHandleBase_.

Definition at line 167 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 335 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 284 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 149 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 152 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 154 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 84 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 151 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 159 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 158 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 157 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 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>
uint8_t ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::message_out[OUTPUT_SIZE]
protected

Definition at line 93 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 144 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 90 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 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>
Publisher* ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::publishers[MAX_PUBLISHERS]
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>
rosserial_msgs::RequestParamResponse ros::NodeHandle_< Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE >::req_param_resp
private

Definition at line 473 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 87 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 90 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 96 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 150 of file node_handle.h.


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


cob_hand_bridge
Author(s): Mathias Lüdtke
autogenerated on Tue Oct 20 2020 03:35:58