TopicInfo.h
Go to the documentation of this file.
00001 #ifndef _ROS_rosserial_msgs_TopicInfo_h
00002 #define _ROS_rosserial_msgs_TopicInfo_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 
00009 namespace rosserial_msgs
00010 {
00011 
00012   class TopicInfo : public ros::Msg
00013   {
00014     public:
00015       uint16_t topic_id;
00016       const char* topic_name;
00017       const char* message_type;
00018       const char* md5sum;
00019       int32_t buffer_size;
00020       enum { ID_PUBLISHER = 0 };
00021       enum { ID_SUBSCRIBER = 1 };
00022       enum { ID_SERVICE_SERVER = 2 };
00023       enum { ID_SERVICE_CLIENT = 4 };
00024       enum { ID_PARAMETER_REQUEST = 6 };
00025       enum { ID_LOG = 7 };
00026       enum { ID_TIME = 10 };
00027       enum { ID_TX_STOP = 11 };
00028 
00029     virtual int serialize(unsigned char *outbuffer) const
00030     {
00031       int offset = 0;
00032       *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF;
00033       *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF;
00034       offset += sizeof(this->topic_id);
00035       uint32_t length_topic_name = strlen(this->topic_name);
00036       memcpy(outbuffer + offset, &length_topic_name, sizeof(uint32_t));
00037       offset += 4;
00038       memcpy(outbuffer + offset, this->topic_name, length_topic_name);
00039       offset += length_topic_name;
00040       uint32_t length_message_type = strlen(this->message_type);
00041       memcpy(outbuffer + offset, &length_message_type, sizeof(uint32_t));
00042       offset += 4;
00043       memcpy(outbuffer + offset, this->message_type, length_message_type);
00044       offset += length_message_type;
00045       uint32_t length_md5sum = strlen(this->md5sum);
00046       memcpy(outbuffer + offset, &length_md5sum, sizeof(uint32_t));
00047       offset += 4;
00048       memcpy(outbuffer + offset, this->md5sum, length_md5sum);
00049       offset += length_md5sum;
00050       union {
00051         int32_t real;
00052         uint32_t base;
00053       } u_buffer_size;
00054       u_buffer_size.real = this->buffer_size;
00055       *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF;
00056       *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF;
00057       *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF;
00058       *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF;
00059       offset += sizeof(this->buffer_size);
00060       return offset;
00061     }
00062 
00063     virtual int deserialize(unsigned char *inbuffer)
00064     {
00065       int offset = 0;
00066       this->topic_id =  ((uint16_t) (*(inbuffer + offset)));
00067       this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00068       offset += sizeof(this->topic_id);
00069       uint32_t length_topic_name;
00070       memcpy(&length_topic_name, (inbuffer + offset), sizeof(uint32_t));
00071       offset += 4;
00072       for(unsigned int k= offset; k< offset+length_topic_name; ++k){
00073           inbuffer[k-1]=inbuffer[k];
00074       }
00075       inbuffer[offset+length_topic_name-1]=0;
00076       this->topic_name = (char *)(inbuffer + offset-1);
00077       offset += length_topic_name;
00078       uint32_t length_message_type;
00079       memcpy(&length_message_type, (inbuffer + offset), sizeof(uint32_t));
00080       offset += 4;
00081       for(unsigned int k= offset; k< offset+length_message_type; ++k){
00082           inbuffer[k-1]=inbuffer[k];
00083       }
00084       inbuffer[offset+length_message_type-1]=0;
00085       this->message_type = (char *)(inbuffer + offset-1);
00086       offset += length_message_type;
00087       uint32_t length_md5sum;
00088       memcpy(&length_md5sum, (inbuffer + offset), sizeof(uint32_t));
00089       offset += 4;
00090       for(unsigned int k= offset; k< offset+length_md5sum; ++k){
00091           inbuffer[k-1]=inbuffer[k];
00092       }
00093       inbuffer[offset+length_md5sum-1]=0;
00094       this->md5sum = (char *)(inbuffer + offset-1);
00095       offset += length_md5sum;
00096       union {
00097         int32_t real;
00098         uint32_t base;
00099       } u_buffer_size;
00100       u_buffer_size.base = 0;
00101       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00102       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00103       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00104       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00105       this->buffer_size = u_buffer_size.real;
00106       offset += sizeof(this->buffer_size);
00107      return offset;
00108     }
00109 
00110     const char * getType(){ return "rosserial_msgs/TopicInfo"; };
00111     const char * getMD5(){ return "0ad51f88fc44892f8c10684077646005"; };
00112 
00113   };
00114 
00115 }
00116 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:50