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_RegionOfInterest_h
nucho 0:77afd7560544 2 #define ros_RegionOfInterest_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
nucho 0:77afd7560544 9 namespace sensor_msgs
nucho 0:77afd7560544 10 {
nucho 0:77afd7560544 11
nucho 0:77afd7560544 12 class RegionOfInterest : public ros::Msg
nucho 0:77afd7560544 13 {
nucho 0:77afd7560544 14 public:
nucho 0:77afd7560544 15 unsigned long x_offset;
nucho 0:77afd7560544 16 unsigned long y_offset;
nucho 0:77afd7560544 17 unsigned long height;
nucho 0:77afd7560544 18 unsigned long width;
nucho 0:77afd7560544 19 bool do_rectify;
nucho 0:77afd7560544 20
nucho 0:77afd7560544 21 virtual int serialize(unsigned char *outbuffer)
nucho 0:77afd7560544 22 {
nucho 0:77afd7560544 23 int offset = 0;
nucho 0:77afd7560544 24 union {
nucho 0:77afd7560544 25 unsigned long real;
nucho 0:77afd7560544 26 unsigned long base;
nucho 0:77afd7560544 27 } u_x_offset;
nucho 0:77afd7560544 28 u_x_offset.real = this->x_offset;
nucho 0:77afd7560544 29 *(outbuffer + offset + 0) = (u_x_offset.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 30 *(outbuffer + offset + 1) = (u_x_offset.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 31 *(outbuffer + offset + 2) = (u_x_offset.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 32 *(outbuffer + offset + 3) = (u_x_offset.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 33 offset += sizeof(this->x_offset);
nucho 0:77afd7560544 34 union {
nucho 0:77afd7560544 35 unsigned long real;
nucho 0:77afd7560544 36 unsigned long base;
nucho 0:77afd7560544 37 } u_y_offset;
nucho 0:77afd7560544 38 u_y_offset.real = this->y_offset;
nucho 0:77afd7560544 39 *(outbuffer + offset + 0) = (u_y_offset.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 40 *(outbuffer + offset + 1) = (u_y_offset.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 41 *(outbuffer + offset + 2) = (u_y_offset.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 42 *(outbuffer + offset + 3) = (u_y_offset.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 43 offset += sizeof(this->y_offset);
nucho 0:77afd7560544 44 union {
nucho 0:77afd7560544 45 unsigned long real;
nucho 0:77afd7560544 46 unsigned long base;
nucho 0:77afd7560544 47 } u_height;
nucho 0:77afd7560544 48 u_height.real = this->height;
nucho 0:77afd7560544 49 *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 50 *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 51 *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 52 *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 53 offset += sizeof(this->height);
nucho 0:77afd7560544 54 union {
nucho 0:77afd7560544 55 unsigned long real;
nucho 0:77afd7560544 56 unsigned long base;
nucho 0:77afd7560544 57 } u_width;
nucho 0:77afd7560544 58 u_width.real = this->width;
nucho 0:77afd7560544 59 *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 60 *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 61 *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 62 *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 63 offset += sizeof(this->width);
nucho 0:77afd7560544 64 union {
nucho 0:77afd7560544 65 bool real;
nucho 0:77afd7560544 66 unsigned char base;
nucho 0:77afd7560544 67 } u_do_rectify;
nucho 0:77afd7560544 68 u_do_rectify.real = this->do_rectify;
nucho 0:77afd7560544 69 *(outbuffer + offset + 0) = (u_do_rectify.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 70 offset += sizeof(this->do_rectify);
nucho 0:77afd7560544 71 return offset;
nucho 0:77afd7560544 72 }
nucho 0:77afd7560544 73
nucho 0:77afd7560544 74 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 75 {
nucho 0:77afd7560544 76 int offset = 0;
nucho 0:77afd7560544 77 union {
nucho 0:77afd7560544 78 unsigned long real;
nucho 0:77afd7560544 79 unsigned long base;
nucho 0:77afd7560544 80 } u_x_offset;
nucho 0:77afd7560544 81 u_x_offset.base = 0;
nucho 0:77afd7560544 82 u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 83 u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 84 u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 85 u_x_offset.base |= ((typeof(u_x_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 86 this->x_offset = u_x_offset.real;
nucho 0:77afd7560544 87 offset += sizeof(this->x_offset);
nucho 0:77afd7560544 88 union {
nucho 0:77afd7560544 89 unsigned long real;
nucho 0:77afd7560544 90 unsigned long base;
nucho 0:77afd7560544 91 } u_y_offset;
nucho 0:77afd7560544 92 u_y_offset.base = 0;
nucho 0:77afd7560544 93 u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 94 u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 95 u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 96 u_y_offset.base |= ((typeof(u_y_offset.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 97 this->y_offset = u_y_offset.real;
nucho 0:77afd7560544 98 offset += sizeof(this->y_offset);
nucho 0:77afd7560544 99 union {
nucho 0:77afd7560544 100 unsigned long real;
nucho 0:77afd7560544 101 unsigned long base;
nucho 0:77afd7560544 102 } u_height;
nucho 0:77afd7560544 103 u_height.base = 0;
nucho 0:77afd7560544 104 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 105 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 106 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 107 u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 108 this->height = u_height.real;
nucho 0:77afd7560544 109 offset += sizeof(this->height);
nucho 0:77afd7560544 110 union {
nucho 0:77afd7560544 111 unsigned long real;
nucho 0:77afd7560544 112 unsigned long base;
nucho 0:77afd7560544 113 } u_width;
nucho 0:77afd7560544 114 u_width.base = 0;
nucho 0:77afd7560544 115 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 116 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 117 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 118 u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 119 this->width = u_width.real;
nucho 0:77afd7560544 120 offset += sizeof(this->width);
nucho 0:77afd7560544 121 union {
nucho 0:77afd7560544 122 bool real;
nucho 0:77afd7560544 123 unsigned char base;
nucho 0:77afd7560544 124 } u_do_rectify;
nucho 0:77afd7560544 125 u_do_rectify.base = 0;
nucho 0:77afd7560544 126 u_do_rectify.base |= ((typeof(u_do_rectify.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 127 this->do_rectify = u_do_rectify.real;
nucho 0:77afd7560544 128 offset += sizeof(this->do_rectify);
nucho 0:77afd7560544 129 return offset;
nucho 0:77afd7560544 130 }
nucho 0:77afd7560544 131
nucho 0:77afd7560544 132 virtual const char * getType(){ return "sensor_msgs/RegionOfInterest"; };
nucho 0:77afd7560544 133
nucho 0:77afd7560544 134 };
nucho 0:77afd7560544 135
nucho 0:77afd7560544 136 }
nucho 0:77afd7560544 137 #endif