35 #ifndef ROS_SUBSCRIBER_H_ 36 #define ROS_SUBSCRIBER_H_ 38 #include "rosserial_msgs/TopicInfo.h" 47 virtual void callback(
unsigned char *data) = 0;
59 template<
typename MsgT,
typename ObjT =
void>
63 typedef void(ObjT::*CallbackT)(
const MsgT&);
66 Subscriber(
const char * topic_name, CallbackT cb, ObjT* obj,
int endpoint = rosserial_msgs::TopicInfo::ID_SUBSCRIBER) :
74 virtual void callback(
unsigned char* data)
76 msg.deserialize(data);
82 return this->msg.getType();
86 return this->msg.getMD5();
100 template<
typename MsgT>
104 typedef void(*CallbackT)(
const MsgT&);
107 Subscriber(
const char * topic_name, CallbackT cb,
int endpoint = rosserial_msgs::TopicInfo::ID_SUBSCRIBER) :
116 msg.deserialize(data);
122 return this->msg.getType();
126 return this->msg.getMD5();
Subscriber(const char *topic_name, CallbackT cb, int endpoint=rosserial_msgs::TopicInfo::ID_SUBSCRIBER)
virtual int getEndpointType()
virtual const char * getMsgMD5()
virtual void callback(unsigned char *data)=0
virtual int getEndpointType()=0
virtual const char * getMsgType()
virtual const char * getMsgMD5()=0
virtual void callback(unsigned char *data)
virtual const char * getMsgType()=0