modify for Hydro version
Fork of rosserial_mbed_lib by
sensor_msgs/Image.h@6:3c54bc7badd4, 2013-10-26 (annotated)
- Committer:
- jjzak
- Date:
- Sat Oct 26 15:39:01 2013 +0000
- Revision:
- 6:3c54bc7badd4
modify for Hydro version;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
jjzak | 6:3c54bc7badd4 | 1 | #ifndef _ROS_sensor_msgs_Image_h |
jjzak | 6:3c54bc7badd4 | 2 | #define _ROS_sensor_msgs_Image_h |
jjzak | 6:3c54bc7badd4 | 3 | |
jjzak | 6:3c54bc7badd4 | 4 | #include <stdint.h> |
jjzak | 6:3c54bc7badd4 | 5 | #include <string.h> |
jjzak | 6:3c54bc7badd4 | 6 | #include <stdlib.h> |
jjzak | 6:3c54bc7badd4 | 7 | #include "ros/msg.h" |
jjzak | 6:3c54bc7badd4 | 8 | #include "std_msgs/Header.h" |
jjzak | 6:3c54bc7badd4 | 9 | |
jjzak | 6:3c54bc7badd4 | 10 | namespace sensor_msgs |
jjzak | 6:3c54bc7badd4 | 11 | { |
jjzak | 6:3c54bc7badd4 | 12 | |
jjzak | 6:3c54bc7badd4 | 13 | class Image : public ros::Msg |
jjzak | 6:3c54bc7badd4 | 14 | { |
jjzak | 6:3c54bc7badd4 | 15 | public: |
jjzak | 6:3c54bc7badd4 | 16 | std_msgs::Header header; |
jjzak | 6:3c54bc7badd4 | 17 | uint32_t height; |
jjzak | 6:3c54bc7badd4 | 18 | uint32_t width; |
jjzak | 6:3c54bc7badd4 | 19 | char * encoding; |
jjzak | 6:3c54bc7badd4 | 20 | uint8_t is_bigendian; |
jjzak | 6:3c54bc7badd4 | 21 | uint32_t step; |
jjzak | 6:3c54bc7badd4 | 22 | uint8_t data_length; |
jjzak | 6:3c54bc7badd4 | 23 | uint8_t st_data; |
jjzak | 6:3c54bc7badd4 | 24 | uint8_t * data; |
jjzak | 6:3c54bc7badd4 | 25 | |
jjzak | 6:3c54bc7badd4 | 26 | virtual int serialize(unsigned char *outbuffer) const |
jjzak | 6:3c54bc7badd4 | 27 | { |
jjzak | 6:3c54bc7badd4 | 28 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 29 | offset += this->header.serialize(outbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 30 | *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 31 | *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 32 | *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 33 | *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 34 | offset += sizeof(this->height); |
jjzak | 6:3c54bc7badd4 | 35 | *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 36 | *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 37 | *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 38 | *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 39 | offset += sizeof(this->width); |
jjzak | 6:3c54bc7badd4 | 40 | uint32_t length_encoding = strlen( (const char*) this->encoding); |
jjzak | 6:3c54bc7badd4 | 41 | memcpy(outbuffer + offset, &length_encoding, sizeof(uint32_t)); |
jjzak | 6:3c54bc7badd4 | 42 | offset += 4; |
jjzak | 6:3c54bc7badd4 | 43 | memcpy(outbuffer + offset, this->encoding, length_encoding); |
jjzak | 6:3c54bc7badd4 | 44 | offset += length_encoding; |
jjzak | 6:3c54bc7badd4 | 45 | *(outbuffer + offset + 0) = (this->is_bigendian >> (8 * 0)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 46 | offset += sizeof(this->is_bigendian); |
jjzak | 6:3c54bc7badd4 | 47 | *(outbuffer + offset + 0) = (this->step >> (8 * 0)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 48 | *(outbuffer + offset + 1) = (this->step >> (8 * 1)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 49 | *(outbuffer + offset + 2) = (this->step >> (8 * 2)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 50 | *(outbuffer + offset + 3) = (this->step >> (8 * 3)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 51 | offset += sizeof(this->step); |
jjzak | 6:3c54bc7badd4 | 52 | *(outbuffer + offset++) = data_length; |
jjzak | 6:3c54bc7badd4 | 53 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 54 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 55 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 56 | for( uint8_t i = 0; i < data_length; i++){ |
jjzak | 6:3c54bc7badd4 | 57 | *(outbuffer + offset + 0) = (this->data[i] >> (8 * 0)) & 0xFF; |
jjzak | 6:3c54bc7badd4 | 58 | offset += sizeof(this->data[i]); |
jjzak | 6:3c54bc7badd4 | 59 | } |
jjzak | 6:3c54bc7badd4 | 60 | return offset; |
jjzak | 6:3c54bc7badd4 | 61 | } |
jjzak | 6:3c54bc7badd4 | 62 | |
jjzak | 6:3c54bc7badd4 | 63 | virtual int deserialize(unsigned char *inbuffer) |
jjzak | 6:3c54bc7badd4 | 64 | { |
jjzak | 6:3c54bc7badd4 | 65 | int offset = 0; |
jjzak | 6:3c54bc7badd4 | 66 | offset += this->header.deserialize(inbuffer + offset); |
jjzak | 6:3c54bc7badd4 | 67 | this->height = ((uint32_t) (*(inbuffer + offset))); |
jjzak | 6:3c54bc7badd4 | 68 | this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
jjzak | 6:3c54bc7badd4 | 69 | this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
jjzak | 6:3c54bc7badd4 | 70 | this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
jjzak | 6:3c54bc7badd4 | 71 | offset += sizeof(this->height); |
jjzak | 6:3c54bc7badd4 | 72 | this->width = ((uint32_t) (*(inbuffer + offset))); |
jjzak | 6:3c54bc7badd4 | 73 | this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
jjzak | 6:3c54bc7badd4 | 74 | this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
jjzak | 6:3c54bc7badd4 | 75 | this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
jjzak | 6:3c54bc7badd4 | 76 | offset += sizeof(this->width); |
jjzak | 6:3c54bc7badd4 | 77 | uint32_t length_encoding; |
jjzak | 6:3c54bc7badd4 | 78 | memcpy(&length_encoding, (inbuffer + offset), sizeof(uint32_t)); |
jjzak | 6:3c54bc7badd4 | 79 | offset += 4; |
jjzak | 6:3c54bc7badd4 | 80 | for(unsigned int k= offset; k< offset+length_encoding; ++k){ |
jjzak | 6:3c54bc7badd4 | 81 | inbuffer[k-1]=inbuffer[k]; |
jjzak | 6:3c54bc7badd4 | 82 | } |
jjzak | 6:3c54bc7badd4 | 83 | inbuffer[offset+length_encoding-1]=0; |
jjzak | 6:3c54bc7badd4 | 84 | this->encoding = (char *)(inbuffer + offset-1); |
jjzak | 6:3c54bc7badd4 | 85 | offset += length_encoding; |
jjzak | 6:3c54bc7badd4 | 86 | this->is_bigendian = ((uint8_t) (*(inbuffer + offset))); |
jjzak | 6:3c54bc7badd4 | 87 | offset += sizeof(this->is_bigendian); |
jjzak | 6:3c54bc7badd4 | 88 | this->step = ((uint32_t) (*(inbuffer + offset))); |
jjzak | 6:3c54bc7badd4 | 89 | this->step |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
jjzak | 6:3c54bc7badd4 | 90 | this->step |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
jjzak | 6:3c54bc7badd4 | 91 | this->step |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
jjzak | 6:3c54bc7badd4 | 92 | offset += sizeof(this->step); |
jjzak | 6:3c54bc7badd4 | 93 | uint8_t data_lengthT = *(inbuffer + offset++); |
jjzak | 6:3c54bc7badd4 | 94 | if(data_lengthT > data_length) |
jjzak | 6:3c54bc7badd4 | 95 | this->data = (uint8_t*)realloc(this->data, data_lengthT * sizeof(uint8_t)); |
jjzak | 6:3c54bc7badd4 | 96 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 97 | data_length = data_lengthT; |
jjzak | 6:3c54bc7badd4 | 98 | for( uint8_t i = 0; i < data_length; i++){ |
jjzak | 6:3c54bc7badd4 | 99 | this->st_data = ((uint8_t) (*(inbuffer + offset))); |
jjzak | 6:3c54bc7badd4 | 100 | offset += sizeof(this->st_data); |
jjzak | 6:3c54bc7badd4 | 101 | memcpy( &(this->data[i]), &(this->st_data), sizeof(uint8_t)); |
jjzak | 6:3c54bc7badd4 | 102 | } |
jjzak | 6:3c54bc7badd4 | 103 | return offset; |
jjzak | 6:3c54bc7badd4 | 104 | } |
jjzak | 6:3c54bc7badd4 | 105 | |
jjzak | 6:3c54bc7badd4 | 106 | const char * getType(){ return "sensor_msgs/Image"; }; |
jjzak | 6:3c54bc7badd4 | 107 | const char * getMD5(){ return "060021388200f6f0f447d0fcd9c64743"; }; |
jjzak | 6:3c54bc7badd4 | 108 | |
jjzak | 6:3c54bc7badd4 | 109 | }; |
jjzak | 6:3c54bc7badd4 | 110 | |
jjzak | 6:3c54bc7badd4 | 111 | } |
jjzak | 6:3c54bc7badd4 | 112 | #endif |