#include <subscriber.h>
Public Types | |
typedef void(* | CallbackT )(const MsgT &) |
Public Member Functions | |
Subscriber (const char *topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER) | |
virtual void | callback (unsigned char *data) |
virtual const char * | getMsgType () |
virtual const char * | getMsgMD5 () |
virtual int | getEndpointType () |
Public Attributes | |
MsgT | msg |
![]() | |
int | id_ |
const char * | topic_ |
Private Attributes | |
CallbackT | cb_ |
int | endpoint_ |
typedef void(* ros::Subscriber< MsgT >::CallbackT)(const MsgT &) |
|
inline |
|
inlinevirtual |
Implements ros::Subscriber_.
|
inlinevirtual |
Implements ros::Subscriber_.
|
inlinevirtual |
Implements ros::Subscriber_.
|
inlinevirtual |
Implements ros::Subscriber_.
|
private |
|
private |
MsgT ros::Subscriber< MsgT >::msg |