nucho / Mbed 2 deprecated rosserial_mbed

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