Go to the documentation of this file.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 unsigned long seq;
00017 ros::Time stamp;
00018 char * frame_id;
00019
00020 virtual int serialize(unsigned char *outbuffer)
00021 {
00022 int offset = 0;
00023 union {
00024 unsigned long real;
00025 unsigned long base;
00026 } u_seq;
00027 u_seq.real = this->seq;
00028 *(outbuffer + offset + 0) = (u_seq.base >> (8 * 0)) & 0xFF;
00029 *(outbuffer + offset + 1) = (u_seq.base >> (8 * 1)) & 0xFF;
00030 *(outbuffer + offset + 2) = (u_seq.base >> (8 * 2)) & 0xFF;
00031 *(outbuffer + offset + 3) = (u_seq.base >> (8 * 3)) & 0xFF;
00032 offset += sizeof(this->seq);
00033 union {
00034 unsigned long real;
00035 unsigned long base;
00036 } u_sec;
00037 u_sec.real = this->stamp.sec;
00038 *(outbuffer + offset + 0) = (u_sec.base >> (8 * 0)) & 0xFF;
00039 *(outbuffer + offset + 1) = (u_sec.base >> (8 * 1)) & 0xFF;
00040 *(outbuffer + offset + 2) = (u_sec.base >> (8 * 2)) & 0xFF;
00041 *(outbuffer + offset + 3) = (u_sec.base >> (8 * 3)) & 0xFF;
00042 offset += sizeof(this->stamp.sec);
00043 union {
00044 unsigned long real;
00045 unsigned long base;
00046 } u_nsec;
00047 u_nsec.real = this->stamp.nsec;
00048 *(outbuffer + offset + 0) = (u_nsec.base >> (8 * 0)) & 0xFF;
00049 *(outbuffer + offset + 1) = (u_nsec.base >> (8 * 1)) & 0xFF;
00050 *(outbuffer + offset + 2) = (u_nsec.base >> (8 * 2)) & 0xFF;
00051 *(outbuffer + offset + 3) = (u_nsec.base >> (8 * 3)) & 0xFF;
00052 offset += sizeof(this->stamp.nsec);
00053 long * length_frame_id = (long *)(outbuffer + offset);
00054 *length_frame_id = strlen( (const char*) this->frame_id);
00055 offset += 4;
00056 memcpy(outbuffer + offset, this->frame_id, *length_frame_id);
00057 offset += *length_frame_id;
00058 return offset;
00059 }
00060
00061 virtual int deserialize(unsigned char *inbuffer)
00062 {
00063 int offset = 0;
00064 union {
00065 unsigned long real;
00066 unsigned long base;
00067 } u_seq;
00068 u_seq.base = 0;
00069 u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00070 u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00071 u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00072 u_seq.base |= ((typeof(u_seq.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00073 this->seq = u_seq.real;
00074 offset += sizeof(this->seq);
00075 union {
00076 unsigned long real;
00077 unsigned long base;
00078 } u_sec;
00079 u_sec.base = 0;
00080 u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00081 u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00082 u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00083 u_sec.base |= ((typeof(u_sec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00084 this->stamp.sec = u_sec.real;
00085 offset += sizeof(this->stamp.sec);
00086 union {
00087 unsigned long real;
00088 unsigned long base;
00089 } u_nsec;
00090 u_nsec.base = 0;
00091 u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 0))) << (8 * 0);
00092 u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 1))) << (8 * 1);
00093 u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 2))) << (8 * 2);
00094 u_nsec.base |= ((typeof(u_nsec.base)) (*(inbuffer + offset + 3))) << (8 * 3);
00095 this->stamp.nsec = u_nsec.real;
00096 offset += sizeof(this->stamp.nsec);
00097 uint32_t length_frame_id = *(uint32_t *)(inbuffer + offset);
00098 offset += 4;
00099 for(unsigned int k= offset; k< offset+length_frame_id; ++k){
00100 inbuffer[k-1]=inbuffer[k];
00101 }
00102 inbuffer[offset+length_frame_id-1]=0;
00103 this->frame_id = (char *)(inbuffer + offset-1);
00104 offset += length_frame_id;
00105 return offset;
00106 }
00107
00108 const char * getType(){ return "std_msgs/Header"; };
00109
00110 };
00111
00112 }
00113 #endif