Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Image.h
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 typedef std_msgs::Header _header_type; 00017 _header_type header; 00018 typedef uint32_t _height_type; 00019 _height_type height; 00020 typedef uint32_t _width_type; 00021 _width_type width; 00022 typedef const char* _encoding_type; 00023 _encoding_type encoding; 00024 typedef uint8_t _is_bigendian_type; 00025 _is_bigendian_type is_bigendian; 00026 typedef uint32_t _step_type; 00027 _step_type step; 00028 uint32_t data_length; 00029 typedef uint8_t _data_type; 00030 _data_type st_data; 00031 _data_type * data; 00032 00033 Image(): 00034 header(), 00035 height(0), 00036 width(0), 00037 encoding(""), 00038 is_bigendian(0), 00039 step(0), 00040 data_length(0), data(NULL) 00041 { 00042 } 00043 00044 virtual int serialize(unsigned char *outbuffer) const 00045 { 00046 int offset = 0; 00047 offset += this->header.serialize(outbuffer + offset); 00048 *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; 00049 *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; 00050 *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; 00051 *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; 00052 offset += sizeof(this->height); 00053 *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; 00054 *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; 00055 *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; 00056 *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; 00057 offset += sizeof(this->width); 00058 uint32_t length_encoding = strlen(this->encoding); 00059 varToArr(outbuffer + offset, length_encoding); 00060 offset += 4; 00061 memcpy(outbuffer + offset, this->encoding, length_encoding); 00062 offset += length_encoding; 00063 *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF; 00064 offset += sizeof(this->is_bigendian); 00065 *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF; 00066 *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF; 00067 *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF; 00068 *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF; 00069 offset += sizeof(this->step); 00070 *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; 00071 *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; 00072 *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; 00073 *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; 00074 offset += sizeof(this->data_length); 00075 for( uint32_t i = 0; i < data_length; i++){ 00076 *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; 00077 offset += sizeof(this->data[i]); 00078 } 00079 return offset; 00080 } 00081 00082 virtual int deserialize(unsigned char *inbuffer) 00083 { 00084 int offset = 0; 00085 offset += this->header.deserialize(inbuffer + offset); 00086 this->height = ((uint32_t) (*(inbuffer + offset))); 00087 this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00088 this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00089 this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00090 offset += sizeof(this->height); 00091 this->width = ((uint32_t) (*(inbuffer + offset))); 00092 this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00093 this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00094 this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00095 offset += sizeof(this->width); 00096 uint32_t length_encoding; 00097 arrToVar(length_encoding, (inbuffer + offset)); 00098 offset += 4; 00099 for(unsigned int k= offset; k< offset+length_encoding; ++k){ 00100 inbuffer[k-1]=inbuffer[k]; 00101 } 00102 inbuffer[offset+length_encoding-1]=0; 00103 this->encoding = (char *)(inbuffer + offset-1); 00104 offset += length_encoding; 00105 this->is_bigendian = ((uint8_t) (*(inbuffer + offset))); 00106 offset += sizeof(this->is_bigendian); 00107 this->step = ((uint32_t) (*(inbuffer + offset))); 00108 this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00109 this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00110 this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00111 offset += sizeof(this->step); 00112 uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 00113 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00114 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00115 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00116 offset += sizeof(this->data_length); 00117 if(data_lengthT > data_length) 00118 this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); 00119 data_length = data_lengthT; 00120 for( uint32_t i = 0; i < data_length; i++){ 00121 this->st_data = ((uint8_t) (*(inbuffer + offset))); 00122 offset += sizeof(this->st_data); 00123 memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); 00124 } 00125 return offset; 00126 } 00127 00128 const char * getType(){ return "sensor_msgs/Image"; }; 00129 const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; }; 00130 00131 }; 00132 00133 } 00134 #endif
Generated on Wed Jul 13 2022 23:30:17 by
