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       char * topic_name;
00017       char * message_type;
00018       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 
00028     virtual int serialize(unsigned char *outbuffer) const
00029     {
00030       int offset = 0;
00031       *(outbuffer + offset + 0) = (this->topic_id >> (8 * 0)) & 0xFF;
00032       *(outbuffer + offset + 1) = (this->topic_id >> (8 * 1)) & 0xFF;
00033       offset += sizeof(this->topic_id);
00034       uint32_t length_topic_name = strlen( (const char*) this->topic_name);
00035       memcpy(outbuffer + offset, &length_topic_name, sizeof(uint32_t));
00036       offset += 4;
00037       memcpy(outbuffer + offset, this->topic_name, length_topic_name);
00038       offset += length_topic_name;
00039       uint32_t length_message_type = strlen( (const char*) this->message_type);
00040       memcpy(outbuffer + offset, &length_message_type, sizeof(uint32_t));
00041       offset += 4;
00042       memcpy(outbuffer + offset, this->message_type, length_message_type);
00043       offset += length_message_type;
00044       uint32_t length_md5sum = strlen( (const char*) this->md5sum);
00045       memcpy(outbuffer + offset, &length_md5sum, sizeof(uint32_t));
00046       offset += 4;
00047       memcpy(outbuffer + offset, this->md5sum, length_md5sum);
00048       offset += length_md5sum;
00049       union {
00050         int32_t real;
00051         uint32_t base;
00052       } u_buffer_size;
00053       u_buffer_size.real = this->buffer_size;
00054       *(outbuffer + offset + 0) = (u_buffer_size.base >> (8 * 0)) & 0xFF;
00055       *(outbuffer + offset + 1) = (u_buffer_size.base >> (8 * 1)) & 0xFF;
00056       *(outbuffer + offset + 2) = (u_buffer_size.base >> (8 * 2)) & 0xFF;
00057       *(outbuffer + offset + 3) = (u_buffer_size.base >> (8 * 3)) & 0xFF;
00058       offset += sizeof(this->buffer_size);
00059       return offset;
00060     }
00061 
00062     virtual int deserialize(unsigned char *inbuffer)
00063     {
00064       int offset = 0;
00065       this->topic_id =  ((uint16_t) (*(inbuffer + offset)));
00066       this->topic_id |= ((uint16_t) (*(inbuffer + offset + 1))) << (8 * 1);
00067       offset += sizeof(this->topic_id);
00068       uint32_t length_topic_name;
00069       memcpy(&length_topic_name, (inbuffer + offset), sizeof(uint32_t));
00070       offset += 4;
00071       for(unsigned int k= offset; k< offset+length_topic_name; ++k){
00072           inbuffer[k-1]=inbuffer[k];
00073       }
00074       inbuffer[offset+length_topic_name-1]=0;
00075       this->topic_name = (char *)(inbuffer + offset-1);
00076       offset += length_topic_name;
00077       uint32_t length_message_type;
00078       memcpy(&length_message_type, (inbuffer + offset), sizeof(uint32_t));
00079       offset += 4;
00080       for(unsigned int k= offset; k< offset+length_message_type; ++k){
00081           inbuffer[k-1]=inbuffer[k];
00082       }
00083       inbuffer[offset+length_message_type-1]=0;
00084       this->message_type = (char *)(inbuffer + offset-1);
00085       offset += length_message_type;
00086       uint32_t length_md5sum;
00087       memcpy(&length_md5sum, (inbuffer + offset), sizeof(uint32_t));
00088       offset += 4;
00089       for(unsigned int k= offset; k< offset+length_md5sum; ++k){
00090           inbuffer[k-1]=inbuffer[k];
00091       }
00092       inbuffer[offset+length_md5sum-1]=0;
00093       this->md5sum = (char *)(inbuffer + offset-1);
00094       offset += length_md5sum;
00095       union {
00096         int32_t real;
00097         uint32_t base;
00098       } u_buffer_size;
00099       u_buffer_size.base = 0;
00100       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00101       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00102       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00103       u_buffer_size.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00104       this->buffer_size = u_buffer_size.real;
00105       offset += sizeof(this->buffer_size);
00106      return offset;
00107     }
00108 
00109     const char * getType(){ return "rosserial_msgs/TopicInfo"; };
00110     const char * getMD5(){ return "63aa5e8f1bdd6f35c69fe1a1b9d28e9f"; };
00111 
00112   };
00113 
00114 }
00115 #endif


lizi_arduino
Author(s): RoboTiCan
autogenerated on Wed Aug 26 2015 12:24:23