Personal fork

Dependencies:   MODSERIAL

Dependents:   rosserial_mbed

Fork of rosserial_mbed_lib by nucho

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_Range_h
nucho 0:77afd7560544 2 #define ros_Range_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 Range : 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 char radiation_type;
nucho 0:77afd7560544 18 float field_of_view;
nucho 0:77afd7560544 19 float min_range;
nucho 0:77afd7560544 20 float max_range;
nucho 0:77afd7560544 21 float range;
nucho 0:77afd7560544 22 enum { ULTRASOUND = 0 };
nucho 0:77afd7560544 23 enum { INFRARED = 1 };
nucho 0:77afd7560544 24
nucho 0:77afd7560544 25 virtual int serialize(unsigned char *outbuffer)
nucho 0:77afd7560544 26 {
nucho 0:77afd7560544 27 int offset = 0;
nucho 0:77afd7560544 28 offset += this->header.serialize(outbuffer + offset);
nucho 0:77afd7560544 29 union {
nucho 0:77afd7560544 30 unsigned char real;
nucho 0:77afd7560544 31 unsigned char base;
nucho 0:77afd7560544 32 } u_radiation_type;
nucho 0:77afd7560544 33 u_radiation_type.real = this->radiation_type;
nucho 0:77afd7560544 34 *(outbuffer + offset + 0) = (u_radiation_type.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 35 offset += sizeof(this->radiation_type);
nucho 0:77afd7560544 36 union {
nucho 0:77afd7560544 37 float real;
nucho 0:77afd7560544 38 unsigned long base;
nucho 0:77afd7560544 39 } u_field_of_view;
nucho 0:77afd7560544 40 u_field_of_view.real = this->field_of_view;
nucho 0:77afd7560544 41 *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 42 *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 43 *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 44 *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 45 offset += sizeof(this->field_of_view);
nucho 0:77afd7560544 46 union {
nucho 0:77afd7560544 47 float real;
nucho 0:77afd7560544 48 unsigned long base;
nucho 0:77afd7560544 49 } u_min_range;
nucho 0:77afd7560544 50 u_min_range.real = this->min_range;
nucho 0:77afd7560544 51 *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 52 *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 53 *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 54 *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 55 offset += sizeof(this->min_range);
nucho 0:77afd7560544 56 union {
nucho 0:77afd7560544 57 float real;
nucho 0:77afd7560544 58 unsigned long base;
nucho 0:77afd7560544 59 } u_max_range;
nucho 0:77afd7560544 60 u_max_range.real = this->max_range;
nucho 0:77afd7560544 61 *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 62 *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 63 *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 64 *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 65 offset += sizeof(this->max_range);
nucho 0:77afd7560544 66 union {
nucho 0:77afd7560544 67 float real;
nucho 0:77afd7560544 68 unsigned long base;
nucho 0:77afd7560544 69 } u_range;
nucho 0:77afd7560544 70 u_range.real = this->range;
nucho 0:77afd7560544 71 *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 72 *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF;
nucho 0:77afd7560544 73 *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF;
nucho 0:77afd7560544 74 *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF;
nucho 0:77afd7560544 75 offset += sizeof(this->range);
nucho 0:77afd7560544 76 return offset;
nucho 0:77afd7560544 77 }
nucho 0:77afd7560544 78
nucho 0:77afd7560544 79 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 80 {
nucho 0:77afd7560544 81 int offset = 0;
nucho 0:77afd7560544 82 offset += this->header.deserialize(inbuffer + offset);
nucho 0:77afd7560544 83 union {
nucho 0:77afd7560544 84 unsigned char real;
nucho 0:77afd7560544 85 unsigned char base;
nucho 0:77afd7560544 86 } u_radiation_type;
nucho 0:77afd7560544 87 u_radiation_type.base = 0;
nucho 0:77afd7560544 88 u_radiation_type.base |= ((typeof(u_radiation_type.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 89 this->radiation_type = u_radiation_type.real;
nucho 0:77afd7560544 90 offset += sizeof(this->radiation_type);
nucho 0:77afd7560544 91 union {
nucho 0:77afd7560544 92 float real;
nucho 0:77afd7560544 93 unsigned long base;
nucho 0:77afd7560544 94 } u_field_of_view;
nucho 0:77afd7560544 95 u_field_of_view.base = 0;
nucho 0:77afd7560544 96 u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 97 u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 98 u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 99 u_field_of_view.base |= ((typeof(u_field_of_view.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 100 this->field_of_view = u_field_of_view.real;
nucho 0:77afd7560544 101 offset += sizeof(this->field_of_view);
nucho 0:77afd7560544 102 union {
nucho 0:77afd7560544 103 float real;
nucho 0:77afd7560544 104 unsigned long base;
nucho 0:77afd7560544 105 } u_min_range;
nucho 0:77afd7560544 106 u_min_range.base = 0;
nucho 0:77afd7560544 107 u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 108 u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 109 u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 110 u_min_range.base |= ((typeof(u_min_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 111 this->min_range = u_min_range.real;
nucho 0:77afd7560544 112 offset += sizeof(this->min_range);
nucho 0:77afd7560544 113 union {
nucho 0:77afd7560544 114 float real;
nucho 0:77afd7560544 115 unsigned long base;
nucho 0:77afd7560544 116 } u_max_range;
nucho 0:77afd7560544 117 u_max_range.base = 0;
nucho 0:77afd7560544 118 u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 119 u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 120 u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 121 u_max_range.base |= ((typeof(u_max_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 122 this->max_range = u_max_range.real;
nucho 0:77afd7560544 123 offset += sizeof(this->max_range);
nucho 0:77afd7560544 124 union {
nucho 0:77afd7560544 125 float real;
nucho 0:77afd7560544 126 unsigned long base;
nucho 0:77afd7560544 127 } u_range;
nucho 0:77afd7560544 128 u_range.base = 0;
nucho 0:77afd7560544 129 u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 130 u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 1))) << (8 * 1);
nucho 0:77afd7560544 131 u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 2))) << (8 * 2);
nucho 0:77afd7560544 132 u_range.base |= ((typeof(u_range.base)) (*(inbuffer + offset + 3))) << (8 * 3);
nucho 0:77afd7560544 133 this->range = u_range.real;
nucho 0:77afd7560544 134 offset += sizeof(this->range);
nucho 0:77afd7560544 135 return offset;
nucho 0:77afd7560544 136 }
nucho 0:77afd7560544 137
nucho 0:77afd7560544 138 virtual const char * getType(){ return "sensor_msgs/Range"; };
nucho 0:77afd7560544 139
nucho 0:77afd7560544 140 };
nucho 0:77afd7560544 141
nucho 0:77afd7560544 142 }
nucho 0:77afd7560544 143 #endif