00001 #ifndef _ROS_sensor_msgs_Image_h 00002 #define _ROS_sensor_msgs_Image_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "std_msgs/Header.h" 00009 00010 namespace sensor_msgs 00011 { 00012 00013 class Image : public ros::Msg 00014 { 00015 public: 00016 std_msgs::Header header; 00017 uint32_t height; 00018 uint32_t width; 00019 char * encoding; 00020 uint8_t is_bigendian; 00021 uint32_t step; 00022 uint8_t data_length; 00023 uint8_t st_data; 00024 uint8_t * data; 00025 00026 virtual int serialize(unsigned char *outbuffer) const 00027 { 00028 int offset = 0; 00029 offset += this->header.serialize(outbuffer + offset); 00030 *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; 00031 *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; 00032 *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; 00033 *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; 00034 offset += sizeof(this->height); 00035 *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; 00036 *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; 00037 *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; 00038 *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; 00039 offset += sizeof(this->width); 00040 uint32_t * length_encoding = (uint32_t *)(outbuffer + offset); 00041 *length_encoding = strlen( (const char*) this->encoding); 00042 offset += 4; 00043 memcpy(outbuffer + offset, this->encoding, *length_encoding); 00044 offset += *length_encoding; 00045 *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF; 00046 offset += sizeof(this->is_bigendian); 00047 *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF; 00048 *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF; 00049 *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF; 00050 *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF; 00051 offset += sizeof(this->step); 00052 *(outbuffer + offset++) = data_length; 00053 *(outbuffer + offset++) = 0; 00054 *(outbuffer + offset++) = 0; 00055 *(outbuffer + offset++) = 0; 00056 for( uint8_t i = 0; i < data_length; i++){ 00057 *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; 00058 offset += sizeof(this->data[i]); 00059 } 00060 return offset; 00061 } 00062 00063 virtual int deserialize(unsigned char *inbuffer) 00064 { 00065 int offset = 0; 00066 offset += this->header.deserialize(inbuffer + offset); 00067 this->height |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00068 this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00069 this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00070 this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00071 offset += sizeof(this->height); 00072 this->width |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00073 this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00074 this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00075 this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00076 offset += sizeof(this->width); 00077 uint32_t length_encoding = *(uint32_t *)(inbuffer + offset); 00078 offset += 4; 00079 for(unsigned int k= offset; k< offset+length_encoding; ++k){ 00080 inbuffer[k-1]=inbuffer[k]; 00081 } 00082 inbuffer[offset+length_encoding-1]=0; 00083 this->encoding = (char *)(inbuffer + offset-1); 00084 offset += length_encoding; 00085 this->is_bigendian |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00086 offset += sizeof(this->is_bigendian); 00087 this->step |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00088 this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00089 this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00090 this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00091 offset += sizeof(this->step); 00092 uint8_t data_lengthT = *(inbuffer + offset++); 00093 if(data_lengthT > data_length) 00094 this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); 00095 offset += 3; 00096 data_length = data_lengthT; 00097 for( uint8_t i = 0; i < data_length; i++){ 00098 this->st_data |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00099 offset += sizeof(this->st_data); 00100 memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); 00101 } 00102 return offset; 00103 } 00104 00105 const char * getType(){ return "sensor_msgs/Image"; }; 00106 const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; }; 00107 00108 }; 00109 00110 } 00111 #endif