hairo

Dependencies:   mbed BufferedSerial

Committer:
garyservin
Date:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_sensor_msgs_Range_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_sensor_msgs_Range_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "std_msgs/Header.h"
garyservin 0:9e9b7db60fd5 9
garyservin 0:9e9b7db60fd5 10 namespace sensor_msgs
garyservin 0:9e9b7db60fd5 11 {
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 class Range : public ros::Msg
garyservin 0:9e9b7db60fd5 14 {
garyservin 0:9e9b7db60fd5 15 public:
garyservin 0:9e9b7db60fd5 16 typedef std_msgs::Header _header_type;
garyservin 0:9e9b7db60fd5 17 _header_type header;
garyservin 0:9e9b7db60fd5 18 typedef uint8_t _radiation_type_type;
garyservin 0:9e9b7db60fd5 19 _radiation_type_type radiation_type;
garyservin 0:9e9b7db60fd5 20 typedef float _field_of_view_type;
garyservin 0:9e9b7db60fd5 21 _field_of_view_type field_of_view;
garyservin 0:9e9b7db60fd5 22 typedef float _min_range_type;
garyservin 0:9e9b7db60fd5 23 _min_range_type min_range;
garyservin 0:9e9b7db60fd5 24 typedef float _max_range_type;
garyservin 0:9e9b7db60fd5 25 _max_range_type max_range;
garyservin 0:9e9b7db60fd5 26 typedef float _range_type;
garyservin 0:9e9b7db60fd5 27 _range_type range;
garyservin 0:9e9b7db60fd5 28 enum { ULTRASOUND = 0 };
garyservin 0:9e9b7db60fd5 29 enum { INFRARED = 1 };
garyservin 0:9e9b7db60fd5 30
garyservin 0:9e9b7db60fd5 31 Range():
garyservin 0:9e9b7db60fd5 32 header(),
garyservin 0:9e9b7db60fd5 33 radiation_type(0),
garyservin 0:9e9b7db60fd5 34 field_of_view(0),
garyservin 0:9e9b7db60fd5 35 min_range(0),
garyservin 0:9e9b7db60fd5 36 max_range(0),
garyservin 0:9e9b7db60fd5 37 range(0)
garyservin 0:9e9b7db60fd5 38 {
garyservin 0:9e9b7db60fd5 39 }
garyservin 0:9e9b7db60fd5 40
garyservin 0:9e9b7db60fd5 41 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 42 {
garyservin 0:9e9b7db60fd5 43 int offset = 0;
garyservin 0:9e9b7db60fd5 44 offset += this->header.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 45 *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 46 offset += sizeof(this->radiation_type);
garyservin 0:9e9b7db60fd5 47 union {
garyservin 0:9e9b7db60fd5 48 float real;
garyservin 0:9e9b7db60fd5 49 uint32_t base;
garyservin 0:9e9b7db60fd5 50 } u_field_of_view;
garyservin 0:9e9b7db60fd5 51 u_field_of_view.real = this->field_of_view;
garyservin 0:9e9b7db60fd5 52 *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 53 *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 54 *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 55 *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 56 offset += sizeof(this->field_of_view);
garyservin 0:9e9b7db60fd5 57 union {
garyservin 0:9e9b7db60fd5 58 float real;
garyservin 0:9e9b7db60fd5 59 uint32_t base;
garyservin 0:9e9b7db60fd5 60 } u_min_range;
garyservin 0:9e9b7db60fd5 61 u_min_range.real = this->min_range;
garyservin 0:9e9b7db60fd5 62 *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 63 *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 64 *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 65 *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 66 offset += sizeof(this->min_range);
garyservin 0:9e9b7db60fd5 67 union {
garyservin 0:9e9b7db60fd5 68 float real;
garyservin 0:9e9b7db60fd5 69 uint32_t base;
garyservin 0:9e9b7db60fd5 70 } u_max_range;
garyservin 0:9e9b7db60fd5 71 u_max_range.real = this->max_range;
garyservin 0:9e9b7db60fd5 72 *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 73 *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 74 *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 75 *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 76 offset += sizeof(this->max_range);
garyservin 0:9e9b7db60fd5 77 union {
garyservin 0:9e9b7db60fd5 78 float real;
garyservin 0:9e9b7db60fd5 79 uint32_t base;
garyservin 0:9e9b7db60fd5 80 } u_range;
garyservin 0:9e9b7db60fd5 81 u_range.real = this->range;
garyservin 0:9e9b7db60fd5 82 *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 83 *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 84 *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 85 *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 86 offset += sizeof(this->range);
garyservin 0:9e9b7db60fd5 87 return offset;
garyservin 0:9e9b7db60fd5 88 }
garyservin 0:9e9b7db60fd5 89
garyservin 0:9e9b7db60fd5 90 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 91 {
garyservin 0:9e9b7db60fd5 92 int offset = 0;
garyservin 0:9e9b7db60fd5 93 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 94 this->radiation_type = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 95 offset += sizeof(this->radiation_type);
garyservin 0:9e9b7db60fd5 96 union {
garyservin 0:9e9b7db60fd5 97 float real;
garyservin 0:9e9b7db60fd5 98 uint32_t base;
garyservin 0:9e9b7db60fd5 99 } u_field_of_view;
garyservin 0:9e9b7db60fd5 100 u_field_of_view.base = 0;
garyservin 0:9e9b7db60fd5 101 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 102 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 103 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 104 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 105 this->field_of_view = u_field_of_view.real;
garyservin 0:9e9b7db60fd5 106 offset += sizeof(this->field_of_view);
garyservin 0:9e9b7db60fd5 107 union {
garyservin 0:9e9b7db60fd5 108 float real;
garyservin 0:9e9b7db60fd5 109 uint32_t base;
garyservin 0:9e9b7db60fd5 110 } u_min_range;
garyservin 0:9e9b7db60fd5 111 u_min_range.base = 0;
garyservin 0:9e9b7db60fd5 112 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 113 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 114 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 115 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 116 this->min_range = u_min_range.real;
garyservin 0:9e9b7db60fd5 117 offset += sizeof(this->min_range);
garyservin 0:9e9b7db60fd5 118 union {
garyservin 0:9e9b7db60fd5 119 float real;
garyservin 0:9e9b7db60fd5 120 uint32_t base;
garyservin 0:9e9b7db60fd5 121 } u_max_range;
garyservin 0:9e9b7db60fd5 122 u_max_range.base = 0;
garyservin 0:9e9b7db60fd5 123 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 124 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 125 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 126 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 127 this->max_range = u_max_range.real;
garyservin 0:9e9b7db60fd5 128 offset += sizeof(this->max_range);
garyservin 0:9e9b7db60fd5 129 union {
garyservin 0:9e9b7db60fd5 130 float real;
garyservin 0:9e9b7db60fd5 131 uint32_t base;
garyservin 0:9e9b7db60fd5 132 } u_range;
garyservin 0:9e9b7db60fd5 133 u_range.base = 0;
garyservin 0:9e9b7db60fd5 134 u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 135 u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 136 u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 137 u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 138 this->range = u_range.real;
garyservin 0:9e9b7db60fd5 139 offset += sizeof(this->range);
garyservin 0:9e9b7db60fd5 140 return offset;
garyservin 0:9e9b7db60fd5 141 }
garyservin 0:9e9b7db60fd5 142
garyservin 0:9e9b7db60fd5 143 const char * getType(){ return "sensor_msgs/Range"; };
garyservin 0:9e9b7db60fd5 144 const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; };
garyservin 0:9e9b7db60fd5 145
garyservin 0:9e9b7db60fd5 146 };
garyservin 0:9e9b7db60fd5 147
garyservin 0:9e9b7db60fd5 148 }
garyservin 0:9e9b7db60fd5 149 #endif