18 #ifndef _ROS_rosserial_msgs_TopicInfo_h 19 #define _ROS_rosserial_msgs_TopicInfo_h 55 virtual int serialize(
unsigned char *outbuffer)
const 58 *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF;
59 *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF;
61 uint32_t length_topic_name = strlen(this->topic_name);
62 memcpy(outbuffer + offset, &length_topic_name,
sizeof(uint32_t));
64 memcpy(outbuffer + offset, this->topic_name, length_topic_name);
65 offset += length_topic_name;
66 uint32_t length_message_type = strlen(this->message_type);
67 memcpy(outbuffer + offset, &length_message_type,
sizeof(uint32_t));
69 memcpy(outbuffer + offset, this->message_type, length_message_type);
70 offset += length_message_type;
71 uint32_t length_md5sum = strlen(this->md5sum);
72 memcpy(outbuffer + offset, &length_md5sum,
sizeof(uint32_t));
74 memcpy(outbuffer + offset, this->md5sum, length_md5sum);
75 offset += length_md5sum;
81 *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF;
82 *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF;
83 *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF;
84 *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF;
92 this->topic_id = ((uint16_t) (*(inbuffer + offset)));
93 this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
95 uint32_t length_topic_name;
96 memcpy(&length_topic_name, (inbuffer + offset),
sizeof(uint32_t));
98 for(
unsigned int k= offset; k< offset+length_topic_name; ++k){
99 inbuffer[k-1]=inbuffer[k];
101 inbuffer[offset+length_topic_name-1]=0;
102 this->topic_name = (
char *)(inbuffer + offset-1);
103 offset += length_topic_name;
104 uint32_t length_message_type;
105 memcpy(&length_message_type, (inbuffer + offset),
sizeof(uint32_t));
107 for(
unsigned int k= offset; k< offset+length_message_type; ++k){
108 inbuffer[k-1]=inbuffer[k];
110 inbuffer[offset+length_message_type-1]=0;
111 this->message_type = (
char *)(inbuffer + offset-1);
112 offset += length_message_type;
113 uint32_t length_md5sum;
114 memcpy(&length_md5sum, (inbuffer + offset),
sizeof(uint32_t));
116 for(
unsigned int k= offset; k< offset+length_md5sum; ++k){
117 inbuffer[k-1]=inbuffer[k];
119 inbuffer[offset+length_md5sum-1]=0;
120 this->md5sum = (
char *)(inbuffer + offset-1);
121 offset += length_md5sum;
126 u_buffer_size.base = 0;
127 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
128 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
129 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
130 u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
131 this->buffer_size = u_buffer_size.real;
136 const char *
getType(){
return "rosserial_msgs/TopicInfo"; };
137 const char *
getMD5(){
return "0ad51f88fc44892f8c10684077646005"; };
virtual int serialize(unsigned char *outbuffer) const
virtual int deserialize(unsigned char *inbuffer)
const char * message_type