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:
Fri Aug 19 09:06:30 2011 +0000
Revision:
0:77afd7560544
Child:
3:1cf99502f396

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 0:77afd7560544 1 #ifndef ros_Image_h
nucho 0:77afd7560544 2 #define ros_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 0:77afd7560544 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 0:77afd7560544 17 unsigned long height;
nucho 0:77afd7560544 18 unsigned long width;
nucho 0:77afd7560544 19 char * encoding;
nucho 0:77afd7560544 20 unsigned char is_bigendian;
nucho 0:77afd7560544 21 unsigned long step;
nucho 0:77afd7560544 22 unsigned char data_length;
nucho 0:77afd7560544 23 unsigned char st_data;
nucho 0:77afd7560544 24 unsigned char * data;
nucho 0:77afd7560544 25
nucho 0:77afd7560544 26 virtual int serialize(unsigned char *outbuffer)
nucho 0:77afd7560544 27 {
nucho 0:77afd7560544 28 int offset = 0;
nucho 0:77afd7560544 29 offset += this->header.serialize(outbuffer + offset);
nucho 0:77afd7560544 30 union {
nucho 0:77afd7560544 31 unsigned long real;
nucho 0:77afd7560544 32 unsigned long base;
nucho 0:77afd7560544 33 } u_height;
nucho 0:77afd7560544 34 u_height.real = this->height;
nucho 0:77afd7560544 35 *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 36 *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 37 *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 38 *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 39 offset += sizeof(this->height);
nucho 0:77afd7560544 40 union {
nucho 0:77afd7560544 41 unsigned long real;
nucho 0:77afd7560544 42 unsigned long base;
nucho 0:77afd7560544 43 } u_width;
nucho 0:77afd7560544 44 u_width.real = this->width;
nucho 0:77afd7560544 45 *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 46 *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 47 *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 48 *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 49 offset += sizeof(this->width);
nucho 0:77afd7560544 50 long * length_encoding = (long *)(outbuffer + offset);
nucho 0:77afd7560544 51 *length_encoding = strlen( (const char*) this->encoding);
nucho 0:77afd7560544 52 offset += 4;
nucho 0:77afd7560544 53 memcpy(outbuffer + offset, this->encoding, *length_encoding);
nucho 0:77afd7560544 54 offset += *length_encoding;
nucho 0:77afd7560544 55 union {
nucho 0:77afd7560544 56 unsigned char real;
nucho 0:77afd7560544 57 unsigned char base;
nucho 0:77afd7560544 58 } u_is_bigendian;
nucho 0:77afd7560544 59 u_is_bigendian.real = this->is_bigendian;
nucho 0:77afd7560544 60 *(outbuffer + offset + 0) = (u_is_bigendian.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 61 offset += sizeof(this->is_bigendian);
nucho 0:77afd7560544 62 union {
nucho 0:77afd7560544 63 unsigned long real;
nucho 0:77afd7560544 64 unsigned long base;
nucho 0:77afd7560544 65 } u_step;
nucho 0:77afd7560544 66 u_step.real = this->step;
nucho 0:77afd7560544 67 *(outbuffer + offset + 0) = (u_step.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 68 *(outbuffer + offset + 1) = (u_step.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 69 *(outbuffer + offset + 2) = (u_step.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 70 *(outbuffer + offset + 3) = (u_step.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 71 offset += sizeof(this->step);
nucho 0:77afd7560544 72 *(outbuffer + offset++) = data_length;
nucho 0:77afd7560544 73 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 74 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 75 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 76 for( unsigned char i = 0; i < data_length; i++){
nucho 0:77afd7560544 77 union {
nucho 0:77afd7560544 78 unsigned char real;
nucho 0:77afd7560544 79 unsigned char base;
nucho 0:77afd7560544 80 } u_datai;
nucho 0:77afd7560544 81 u_datai.real = this->data[i];
nucho 0:77afd7560544 82 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 83 offset += sizeof(this->data[i]);
nucho 0:77afd7560544 84 }
nucho 0:77afd7560544 85 return offset;
nucho 0:77afd7560544 86 }
nucho 0:77afd7560544 87
nucho 0:77afd7560544 88 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 89 {
nucho 0:77afd7560544 90 int offset = 0;
nucho 0:77afd7560544 91 offset += this->header.deserialize(inbuffer + offset);
nucho 0:77afd7560544 92 union {
nucho 0:77afd7560544 93 unsigned long real;
nucho 0:77afd7560544 94 unsigned long base;
nucho 0:77afd7560544 95 } u_height;
nucho 0:77afd7560544 96 u_height.base = 0;
nucho 0:77afd7560544 97 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 98 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 99 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 100 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 101 this->height = u_height.real;
nucho 0:77afd7560544 102 offset += sizeof(this->height);
nucho 0:77afd7560544 103 union {
nucho 0:77afd7560544 104 unsigned long real;
nucho 0:77afd7560544 105 unsigned long base;
nucho 0:77afd7560544 106 } u_width;
nucho 0:77afd7560544 107 u_width.base = 0;
nucho 0:77afd7560544 108 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 109 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 110 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 111 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 112 this->width = u_width.real;
nucho 0:77afd7560544 113 offset += sizeof(this->width);
nucho 0:77afd7560544 114 uint32_t length_encoding = *(uint32_t *)(inbuffer + offset);
nucho 0:77afd7560544 115 offset += 4;
nucho 0:77afd7560544 116 for(unsigned int k= offset; k< offset+length_encoding; ++k){
nucho 0:77afd7560544 117 inbuffer[k-1]=inbuffer[k];
nucho 0:77afd7560544 118 }
nucho 0:77afd7560544 119 inbuffer[offset+length_encoding-1]=0;
nucho 0:77afd7560544 120 this->encoding = (char *)(inbuffer + offset-1);
nucho 0:77afd7560544 121 offset += length_encoding;
nucho 0:77afd7560544 122 union {
nucho 0:77afd7560544 123 unsigned char real;
nucho 0:77afd7560544 124 unsigned char base;
nucho 0:77afd7560544 125 } u_is_bigendian;
nucho 0:77afd7560544 126 u_is_bigendian.base = 0;
nucho 0:77afd7560544 127 u_is_bigendian.base |= ((typeof(u_is_bigendian.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 128 this->is_bigendian = u_is_bigendian.real;
nucho 0:77afd7560544 129 offset += sizeof(this->is_bigendian);
nucho 0:77afd7560544 130 union {
nucho 0:77afd7560544 131 unsigned long real;
nucho 0:77afd7560544 132 unsigned long base;
nucho 0:77afd7560544 133 } u_step;
nucho 0:77afd7560544 134 u_step.base = 0;
nucho 0:77afd7560544 135 u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 136 u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 137 u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 138 u_step.base |= ((typeof(u_step.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 139 this->step = u_step.real;
nucho 0:77afd7560544 140 offset += sizeof(this->step);
nucho 0:77afd7560544 141 unsigned char data_lengthT = *(inbuffer + offset++);
nucho 0:77afd7560544 142 if(data_lengthT > data_length)
nucho 0:77afd7560544 143 this->data = (unsigned char*)realloc(this->data, data_lengthT * sizeof(unsigned char));
nucho 0:77afd7560544 144 offset += 3;
nucho 0:77afd7560544 145 data_length = data_lengthT;
nucho 0:77afd7560544 146 for( unsigned char i = 0; i < data_length; i++){
nucho 0:77afd7560544 147 union {
nucho 0:77afd7560544 148 unsigned char real;
nucho 0:77afd7560544 149 unsigned char base;
nucho 0:77afd7560544 150 } u_st_data;
nucho 0:77afd7560544 151 u_st_data.base = 0;
nucho 0:77afd7560544 152 u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 153 this->st_data = u_st_data.real;
nucho 0:77afd7560544 154 offset += sizeof(this->st_data);
nucho 0:77afd7560544 155 memcpy( &(this->data[i]), &(this->st_data), sizeof(unsigned char));
nucho 0:77afd7560544 156 }
nucho 0:77afd7560544 157 return offset;
nucho 0:77afd7560544 158 }
nucho 0:77afd7560544 159
nucho 0:77afd7560544 160 virtual const char * getType(){ return "sensor_msgs/Image"; };
nucho 0:77afd7560544 161
nucho 0:77afd7560544 162 };
nucho 0:77afd7560544 163
nucho 0:77afd7560544 164 }
nucho 0:77afd7560544 165 #endif