This is a fork from the original, including a small change in the buffer size of the hardware interface (increased to 2048) and decreasing the number of publishers and subscribers to 5. Besides, the library about the message Adc.h was modified so as to increase the number of available Adc channels to be read ( from 6 to 7 ) For this modification, a change in checksum was required

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

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_SERVICE_GetPointMapROI_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_SERVICE_GetPointMapROI_h
garyservin 0:9e9b7db60fd5 3 #include <stdint.h>
garyservin 0:9e9b7db60fd5 4 #include <string.h>
garyservin 0:9e9b7db60fd5 5 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 6 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 7 #include "sensor_msgs/PointCloud2.h"
garyservin 0:9e9b7db60fd5 8
garyservin 0:9e9b7db60fd5 9 namespace map_msgs
garyservin 0:9e9b7db60fd5 10 {
garyservin 0:9e9b7db60fd5 11
garyservin 0:9e9b7db60fd5 12 static const char GETPOINTMAPROI[] = "map_msgs/GetPointMapROI";
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 class GetPointMapROIRequest : public ros::Msg
garyservin 0:9e9b7db60fd5 15 {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 typedef double _x_type;
garyservin 0:9e9b7db60fd5 18 _x_type x;
garyservin 0:9e9b7db60fd5 19 typedef double _y_type;
garyservin 0:9e9b7db60fd5 20 _y_type y;
garyservin 0:9e9b7db60fd5 21 typedef double _z_type;
garyservin 0:9e9b7db60fd5 22 _z_type z;
garyservin 0:9e9b7db60fd5 23 typedef double _r_type;
garyservin 0:9e9b7db60fd5 24 _r_type r;
garyservin 0:9e9b7db60fd5 25 typedef double _l_x_type;
garyservin 0:9e9b7db60fd5 26 _l_x_type l_x;
garyservin 0:9e9b7db60fd5 27 typedef double _l_y_type;
garyservin 0:9e9b7db60fd5 28 _l_y_type l_y;
garyservin 0:9e9b7db60fd5 29 typedef double _l_z_type;
garyservin 0:9e9b7db60fd5 30 _l_z_type l_z;
garyservin 0:9e9b7db60fd5 31
garyservin 0:9e9b7db60fd5 32 GetPointMapROIRequest():
garyservin 0:9e9b7db60fd5 33 x(0),
garyservin 0:9e9b7db60fd5 34 y(0),
garyservin 0:9e9b7db60fd5 35 z(0),
garyservin 0:9e9b7db60fd5 36 r(0),
garyservin 0:9e9b7db60fd5 37 l_x(0),
garyservin 0:9e9b7db60fd5 38 l_y(0),
garyservin 0:9e9b7db60fd5 39 l_z(0)
garyservin 0:9e9b7db60fd5 40 {
garyservin 0:9e9b7db60fd5 41 }
garyservin 0:9e9b7db60fd5 42
garyservin 0:9e9b7db60fd5 43 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 44 {
garyservin 0:9e9b7db60fd5 45 int offset = 0;
garyservin 0:9e9b7db60fd5 46 union {
garyservin 0:9e9b7db60fd5 47 double real;
garyservin 0:9e9b7db60fd5 48 uint64_t base;
garyservin 0:9e9b7db60fd5 49 } u_x;
garyservin 0:9e9b7db60fd5 50 u_x.real = this->x;
garyservin 0:9e9b7db60fd5 51 *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 52 *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 53 *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 54 *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 55 *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 56 *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 57 *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 58 *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 59 offset += sizeof(this->x);
garyservin 0:9e9b7db60fd5 60 union {
garyservin 0:9e9b7db60fd5 61 double real;
garyservin 0:9e9b7db60fd5 62 uint64_t base;
garyservin 0:9e9b7db60fd5 63 } u_y;
garyservin 0:9e9b7db60fd5 64 u_y.real = this->y;
garyservin 0:9e9b7db60fd5 65 *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 66 *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 67 *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 68 *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 69 *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 70 *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 71 *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 72 *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 73 offset += sizeof(this->y);
garyservin 0:9e9b7db60fd5 74 union {
garyservin 0:9e9b7db60fd5 75 double real;
garyservin 0:9e9b7db60fd5 76 uint64_t base;
garyservin 0:9e9b7db60fd5 77 } u_z;
garyservin 0:9e9b7db60fd5 78 u_z.real = this->z;
garyservin 0:9e9b7db60fd5 79 *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 80 *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 81 *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 82 *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 83 *(outbuffer + offset + 4) = (u_z.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 84 *(outbuffer + offset + 5) = (u_z.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 85 *(outbuffer + offset + 6) = (u_z.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 86 *(outbuffer + offset + 7) = (u_z.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 87 offset += sizeof(this->z);
garyservin 0:9e9b7db60fd5 88 union {
garyservin 0:9e9b7db60fd5 89 double real;
garyservin 0:9e9b7db60fd5 90 uint64_t base;
garyservin 0:9e9b7db60fd5 91 } u_r;
garyservin 0:9e9b7db60fd5 92 u_r.real = this->r;
garyservin 0:9e9b7db60fd5 93 *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 94 *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 95 *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 96 *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 97 *(outbuffer + offset + 4) = (u_r.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 98 *(outbuffer + offset + 5) = (u_r.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 99 *(outbuffer + offset + 6) = (u_r.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 100 *(outbuffer + offset + 7) = (u_r.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 101 offset += sizeof(this->r);
garyservin 0:9e9b7db60fd5 102 union {
garyservin 0:9e9b7db60fd5 103 double real;
garyservin 0:9e9b7db60fd5 104 uint64_t base;
garyservin 0:9e9b7db60fd5 105 } u_l_x;
garyservin 0:9e9b7db60fd5 106 u_l_x.real = this->l_x;
garyservin 0:9e9b7db60fd5 107 *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 108 *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 109 *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 110 *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 111 *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 112 *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 113 *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 114 *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 115 offset += sizeof(this->l_x);
garyservin 0:9e9b7db60fd5 116 union {
garyservin 0:9e9b7db60fd5 117 double real;
garyservin 0:9e9b7db60fd5 118 uint64_t base;
garyservin 0:9e9b7db60fd5 119 } u_l_y;
garyservin 0:9e9b7db60fd5 120 u_l_y.real = this->l_y;
garyservin 0:9e9b7db60fd5 121 *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 122 *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 123 *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 124 *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 125 *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 126 *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 127 *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 128 *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 129 offset += sizeof(this->l_y);
garyservin 0:9e9b7db60fd5 130 union {
garyservin 0:9e9b7db60fd5 131 double real;
garyservin 0:9e9b7db60fd5 132 uint64_t base;
garyservin 0:9e9b7db60fd5 133 } u_l_z;
garyservin 0:9e9b7db60fd5 134 u_l_z.real = this->l_z;
garyservin 0:9e9b7db60fd5 135 *(outbuffer + offset + 0) = (u_l_z.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 136 *(outbuffer + offset + 1) = (u_l_z.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 137 *(outbuffer + offset + 2) = (u_l_z.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 138 *(outbuffer + offset + 3) = (u_l_z.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 139 *(outbuffer + offset + 4) = (u_l_z.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 140 *(outbuffer + offset + 5) = (u_l_z.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 141 *(outbuffer + offset + 6) = (u_l_z.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 142 *(outbuffer + offset + 7) = (u_l_z.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 143 offset += sizeof(this->l_z);
garyservin 0:9e9b7db60fd5 144 return offset;
garyservin 0:9e9b7db60fd5 145 }
garyservin 0:9e9b7db60fd5 146
garyservin 0:9e9b7db60fd5 147 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 148 {
garyservin 0:9e9b7db60fd5 149 int offset = 0;
garyservin 0:9e9b7db60fd5 150 union {
garyservin 0:9e9b7db60fd5 151 double real;
garyservin 0:9e9b7db60fd5 152 uint64_t base;
garyservin 0:9e9b7db60fd5 153 } u_x;
garyservin 0:9e9b7db60fd5 154 u_x.base = 0;
garyservin 0:9e9b7db60fd5 155 u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 156 u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 157 u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 158 u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 159 u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 160 u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 161 u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 162 u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 163 this->x = u_x.real;
garyservin 0:9e9b7db60fd5 164 offset += sizeof(this->x);
garyservin 0:9e9b7db60fd5 165 union {
garyservin 0:9e9b7db60fd5 166 double real;
garyservin 0:9e9b7db60fd5 167 uint64_t base;
garyservin 0:9e9b7db60fd5 168 } u_y;
garyservin 0:9e9b7db60fd5 169 u_y.base = 0;
garyservin 0:9e9b7db60fd5 170 u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 171 u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 172 u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 173 u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 174 u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 175 u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 176 u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 177 u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 178 this->y = u_y.real;
garyservin 0:9e9b7db60fd5 179 offset += sizeof(this->y);
garyservin 0:9e9b7db60fd5 180 union {
garyservin 0:9e9b7db60fd5 181 double real;
garyservin 0:9e9b7db60fd5 182 uint64_t base;
garyservin 0:9e9b7db60fd5 183 } u_z;
garyservin 0:9e9b7db60fd5 184 u_z.base = 0;
garyservin 0:9e9b7db60fd5 185 u_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 186 u_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 187 u_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 188 u_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 189 u_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 190 u_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 191 u_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 192 u_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 193 this->z = u_z.real;
garyservin 0:9e9b7db60fd5 194 offset += sizeof(this->z);
garyservin 0:9e9b7db60fd5 195 union {
garyservin 0:9e9b7db60fd5 196 double real;
garyservin 0:9e9b7db60fd5 197 uint64_t base;
garyservin 0:9e9b7db60fd5 198 } u_r;
garyservin 0:9e9b7db60fd5 199 u_r.base = 0;
garyservin 0:9e9b7db60fd5 200 u_r.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 201 u_r.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 202 u_r.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 203 u_r.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 204 u_r.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 205 u_r.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 206 u_r.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 207 u_r.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 208 this->r = u_r.real;
garyservin 0:9e9b7db60fd5 209 offset += sizeof(this->r);
garyservin 0:9e9b7db60fd5 210 union {
garyservin 0:9e9b7db60fd5 211 double real;
garyservin 0:9e9b7db60fd5 212 uint64_t base;
garyservin 0:9e9b7db60fd5 213 } u_l_x;
garyservin 0:9e9b7db60fd5 214 u_l_x.base = 0;
garyservin 0:9e9b7db60fd5 215 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 216 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 217 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 218 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 219 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 220 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 221 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 222 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 223 this->l_x = u_l_x.real;
garyservin 0:9e9b7db60fd5 224 offset += sizeof(this->l_x);
garyservin 0:9e9b7db60fd5 225 union {
garyservin 0:9e9b7db60fd5 226 double real;
garyservin 0:9e9b7db60fd5 227 uint64_t base;
garyservin 0:9e9b7db60fd5 228 } u_l_y;
garyservin 0:9e9b7db60fd5 229 u_l_y.base = 0;
garyservin 0:9e9b7db60fd5 230 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 231 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 232 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 233 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 234 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 235 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 236 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 237 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 238 this->l_y = u_l_y.real;
garyservin 0:9e9b7db60fd5 239 offset += sizeof(this->l_y);
garyservin 0:9e9b7db60fd5 240 union {
garyservin 0:9e9b7db60fd5 241 double real;
garyservin 0:9e9b7db60fd5 242 uint64_t base;
garyservin 0:9e9b7db60fd5 243 } u_l_z;
garyservin 0:9e9b7db60fd5 244 u_l_z.base = 0;
garyservin 0:9e9b7db60fd5 245 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 246 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 247 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 248 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 249 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 250 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 251 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 252 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 253 this->l_z = u_l_z.real;
garyservin 0:9e9b7db60fd5 254 offset += sizeof(this->l_z);
garyservin 0:9e9b7db60fd5 255 return offset;
garyservin 0:9e9b7db60fd5 256 }
garyservin 0:9e9b7db60fd5 257
garyservin 0:9e9b7db60fd5 258 const char * getType(){ return GETPOINTMAPROI; };
garyservin 0:9e9b7db60fd5 259 const char * getMD5(){ return "895f7e437a9a6dd225316872b187a303"; };
garyservin 0:9e9b7db60fd5 260
garyservin 0:9e9b7db60fd5 261 };
garyservin 0:9e9b7db60fd5 262
garyservin 0:9e9b7db60fd5 263 class GetPointMapROIResponse : public ros::Msg
garyservin 0:9e9b7db60fd5 264 {
garyservin 0:9e9b7db60fd5 265 public:
garyservin 0:9e9b7db60fd5 266 typedef sensor_msgs::PointCloud2 _sub_map_type;
garyservin 0:9e9b7db60fd5 267 _sub_map_type sub_map;
garyservin 0:9e9b7db60fd5 268
garyservin 0:9e9b7db60fd5 269 GetPointMapROIResponse():
garyservin 0:9e9b7db60fd5 270 sub_map()
garyservin 0:9e9b7db60fd5 271 {
garyservin 0:9e9b7db60fd5 272 }
garyservin 0:9e9b7db60fd5 273
garyservin 0:9e9b7db60fd5 274 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 275 {
garyservin 0:9e9b7db60fd5 276 int offset = 0;
garyservin 0:9e9b7db60fd5 277 offset += this->sub_map.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 278 return offset;
garyservin 0:9e9b7db60fd5 279 }
garyservin 0:9e9b7db60fd5 280
garyservin 0:9e9b7db60fd5 281 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 282 {
garyservin 0:9e9b7db60fd5 283 int offset = 0;
garyservin 0:9e9b7db60fd5 284 offset += this->sub_map.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 285 return offset;
garyservin 0:9e9b7db60fd5 286 }
garyservin 0:9e9b7db60fd5 287
garyservin 0:9e9b7db60fd5 288 const char * getType(){ return GETPOINTMAPROI; };
garyservin 0:9e9b7db60fd5 289 const char * getMD5(){ return "313769f8b0e724525c6463336cbccd63"; };
garyservin 0:9e9b7db60fd5 290
garyservin 0:9e9b7db60fd5 291 };
garyservin 0:9e9b7db60fd5 292
garyservin 0:9e9b7db60fd5 293 class GetPointMapROI {
garyservin 0:9e9b7db60fd5 294 public:
garyservin 0:9e9b7db60fd5 295 typedef GetPointMapROIRequest Request;
garyservin 0:9e9b7db60fd5 296 typedef GetPointMapROIResponse Response;
garyservin 0:9e9b7db60fd5 297 };
garyservin 0:9e9b7db60fd5 298
garyservin 0:9e9b7db60fd5 299 }
garyservin 0:9e9b7db60fd5 300 #endif