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