00001 #ifndef _ROS_std_msgs_Header_h 00002 #define _ROS_std_msgs_Header_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "ros/time.h" 00009 00010 namespace std_msgs 00011 { 00012 00013 class Header : public ros::Msg 00014 { 00015 public: 00016 uint32_t seq; 00017 ros::Time stamp; 00018 char * frame_id; 00019 00020 virtual int serialize(unsigned char *outbuffer) const 00021 { 00022 int offset = 0; 00023 *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF; 00024 *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF; 00025 *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF; 00026 *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF; 00027 offset += sizeof(this->seq); 00028 *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF; 00029 *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF; 00030 *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF; 00031 *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF; 00032 offset += sizeof(this->stamp.sec); 00033 *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF; 00034 *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF; 00035 *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF; 00036 *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF; 00037 offset += sizeof(this->stamp.nsec); 00038 uint32_t * length_frame_id = (uint32_t *)(outbuffer + offset); 00039 *length_frame_id = strlen( (const char*) this->frame_id); 00040 offset += 4; 00041 memcpy(outbuffer + offset, this->frame_id, *length_frame_id); 00042 offset += *length_frame_id; 00043 return offset; 00044 } 00045 00046 virtual int deserialize(unsigned char *inbuffer) 00047 { 00048 int offset = 0; 00049 this->seq |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00050 this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00051 this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00052 this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00053 offset += sizeof(this->seq); 00054 this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00055 this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00056 this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00057 this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00058 offset += sizeof(this->stamp.sec); 00059 this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00060 this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00061 this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00062 this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00063 offset += sizeof(this->stamp.nsec); 00064 uint32_t length_frame_id = *(uint32_t *)(inbuffer + offset); 00065 offset += 4; 00066 for(unsigned int k= offset; k< offset+length_frame_id; ++k){ 00067 inbuffer[k-1]=inbuffer[k]; 00068 } 00069 inbuffer[offset+length_frame_id-1]=0; 00070 this->frame_id = (char *)(inbuffer + offset-1); 00071 offset += length_frame_id; 00072 return offset; 00073 } 00074 00075 const char * getType(){ return "std_msgs/Header"; }; 00076 const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; }; 00077 00078 }; 00079 00080 } 00081 #endif