This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Committer:
nucho
Date:
Wed Feb 29 23:00:21 2012 +0000
Revision:
4:684f39d0c346
Parent:
3:1cf99502f396

        

Who changed what in which revision?

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