Go to the documentation of this file.00001 #ifndef _ROS_nav_msgs_MapMetaData_h
00002 #define _ROS_nav_msgs_MapMetaData_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 #include "geometry_msgs/Pose.h"
00010
00011 namespace nav_msgs
00012 {
00013
00014 class MapMetaData : public ros::Msg
00015 {
00016 public:
00017 ros::Time map_load_time;
00018 float resolution;
00019 uint32_t width;
00020 uint32_t height;
00021 geometry_msgs::Pose origin;
00022
00023 virtual int serialize(unsigned char *outbuffer) const
00024 {
00025 int offset = 0;
00026 *(outbuffer + offset + 0) = (this->map_load_time.sec >> (8 * 0)) & 0xFF;
00027 *(outbuffer + offset + 1) = (this->map_load_time.sec >> (8 * 1)) & 0xFF;
00028 *(outbuffer + offset + 2) = (this->map_load_time.sec >> (8 * 2)) & 0xFF;
00029 *(outbuffer + offset + 3) = (this->map_load_time.sec >> (8 * 3)) & 0xFF;
00030 offset += sizeof(this->map_load_time.sec);
00031 *(outbuffer + offset + 0) = (this->map_load_time.nsec >> (8 * 0)) & 0xFF;
00032 *(outbuffer + offset + 1) = (this->map_load_time.nsec >> (8 * 1)) & 0xFF;
00033 *(outbuffer + offset + 2) = (this->map_load_time.nsec >> (8 * 2)) & 0xFF;
00034 *(outbuffer + offset + 3) = (this->map_load_time.nsec >> (8 * 3)) & 0xFF;
00035 offset += sizeof(this->map_load_time.nsec);
00036 union {
00037 float real;
00038 uint32_t base;
00039 } u_resolution;
00040 u_resolution.real = this->resolution;
00041 *(outbuffer + offset + 0) = (u_resolution.base >> (8 * 0)) & 0xFF;
00042 *(outbuffer + offset + 1) = (u_resolution.base >> (8 * 1)) & 0xFF;
00043 *(outbuffer + offset + 2) = (u_resolution.base >> (8 * 2)) & 0xFF;
00044 *(outbuffer + offset + 3) = (u_resolution.base >> (8 * 3)) & 0xFF;
00045 offset += sizeof(this->resolution);
00046 *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
00047 *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
00048 *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
00049 *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
00050 offset += sizeof(this->width);
00051 *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
00052 *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
00053 *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
00054 *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
00055 offset += sizeof(this->height);
00056 offset += this->origin.serialize(outbuffer + offset);
00057 return offset;
00058 }
00059
00060 virtual int deserialize(unsigned char *inbuffer)
00061 {
00062 int offset = 0;
00063 this->map_load_time.sec = ((uint32_t) (*(inbuffer + offset)));
00064 this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00065 this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00066 this->map_load_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00067 offset += sizeof(this->map_load_time.sec);
00068 this->map_load_time.nsec = ((uint32_t) (*(inbuffer + offset)));
00069 this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00070 this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00071 this->map_load_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00072 offset += sizeof(this->map_load_time.nsec);
00073 union {
00074 float real;
00075 uint32_t base;
00076 } u_resolution;
00077 u_resolution.base = 0;
00078 u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00079 u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00080 u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00081 u_resolution.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00082 this->resolution = u_resolution.real;
00083 offset += sizeof(this->resolution);
00084 this->width = ((uint32_t) (*(inbuffer + offset)));
00085 this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00086 this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00087 this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00088 offset += sizeof(this->width);
00089 this->height = ((uint32_t) (*(inbuffer + offset)));
00090 this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00091 this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00092 this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00093 offset += sizeof(this->height);
00094 offset += this->origin.deserialize(inbuffer + offset);
00095 return offset;
00096 }
00097
00098 const char * getType(){ return "nav_msgs/MapMetaData"; };
00099 const char * getMD5(){ return "10cfc8a2818024d3248802c00c95f11b"; };
00100
00101 };
00102
00103 }
00104 #endif