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

Dependencies:   rosserial_mbed_lib mbed Servo

Committer:
nucho
Date:
Fri Aug 19 09:06:16 2011 +0000
Revision:
0:06fc856e99ca
Child:
3:dff241b66f84

        

Who changed what in which revision?

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