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