Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h
Dependents: WRS2020_mecanum_node
GetPointMapROI.h
00001 #ifndef _ROS_SERVICE_GetPointMapROI_h 00002 #define _ROS_SERVICE_GetPointMapROI_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "sensor_msgs/PointCloud2.h" 00008 00009 namespace map_msgs 00010 { 00011 00012 static const char GETPOINTMAPROI[] = "map_msgs/GetPointMapROI"; 00013 00014 class GetPointMapROIRequest : public ros::Msg 00015 { 00016 public: 00017 typedef double _x_type; 00018 _x_type x; 00019 typedef double _y_type; 00020 _y_type y; 00021 typedef double _z_type; 00022 _z_type z; 00023 typedef double _r_type; 00024 _r_type r; 00025 typedef double _l_x_type; 00026 _l_x_type l_x; 00027 typedef double _l_y_type; 00028 _l_y_type l_y; 00029 typedef double _l_z_type; 00030 _l_z_type l_z; 00031 00032 GetPointMapROIRequest(): 00033 x(0), 00034 y(0), 00035 z(0), 00036 r(0), 00037 l_x(0), 00038 l_y(0), 00039 l_z(0) 00040 { 00041 } 00042 00043 virtual int serialize(unsigned char *outbuffer) const 00044 { 00045 int offset = 0; 00046 union { 00047 double real; 00048 uint64_t base; 00049 } u_x; 00050 u_x.real = this->x; 00051 *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; 00052 *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; 00053 *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; 00054 *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; 00055 *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF; 00056 *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF; 00057 *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF; 00058 *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF; 00059 offset += sizeof(this->x); 00060 union { 00061 double real; 00062 uint64_t base; 00063 } u_y; 00064 u_y.real = this->y; 00065 *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; 00066 *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; 00067 *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; 00068 *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; 00069 *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF; 00070 *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF; 00071 *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF; 00072 *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF; 00073 offset += sizeof(this->y); 00074 union { 00075 double real; 00076 uint64_t base; 00077 } u_z; 00078 u_z.real = this->z; 00079 *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF; 00080 *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF; 00081 *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF; 00082 *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF; 00083 *(outbuffer + offset + 4) = (u_z.base >> (8 * 4)) & 0xFF; 00084 *(outbuffer + offset + 5) = (u_z.base >> (8 * 5)) & 0xFF; 00085 *(outbuffer + offset + 6) = (u_z.base >> (8 * 6)) & 0xFF; 00086 *(outbuffer + offset + 7) = (u_z.base >> (8 * 7)) & 0xFF; 00087 offset += sizeof(this->z); 00088 union { 00089 double real; 00090 uint64_t base; 00091 } u_r; 00092 u_r.real = this->r; 00093 *(outbuffer + offset + 0) = (u_r.base >> (8 * 0)) & 0xFF; 00094 *(outbuffer + offset + 1) = (u_r.base >> (8 * 1)) & 0xFF; 00095 *(outbuffer + offset + 2) = (u_r.base >> (8 * 2)) & 0xFF; 00096 *(outbuffer + offset + 3) = (u_r.base >> (8 * 3)) & 0xFF; 00097 *(outbuffer + offset + 4) = (u_r.base >> (8 * 4)) & 0xFF; 00098 *(outbuffer + offset + 5) = (u_r.base >> (8 * 5)) & 0xFF; 00099 *(outbuffer + offset + 6) = (u_r.base >> (8 * 6)) & 0xFF; 00100 *(outbuffer + offset + 7) = (u_r.base >> (8 * 7)) & 0xFF; 00101 offset += sizeof(this->r); 00102 union { 00103 double real; 00104 uint64_t base; 00105 } u_l_x; 00106 u_l_x.real = this->l_x; 00107 *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF; 00108 *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF; 00109 *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF; 00110 *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF; 00111 *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF; 00112 *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF; 00113 *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF; 00114 *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF; 00115 offset += sizeof(this->l_x); 00116 union { 00117 double real; 00118 uint64_t base; 00119 } u_l_y; 00120 u_l_y.real = this->l_y; 00121 *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF; 00122 *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF; 00123 *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF; 00124 *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF; 00125 *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF; 00126 *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF; 00127 *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF; 00128 *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF; 00129 offset += sizeof(this->l_y); 00130 union { 00131 double real; 00132 uint64_t base; 00133 } u_l_z; 00134 u_l_z.real = this->l_z; 00135 *(outbuffer + offset + 0) = (u_l_z.base >> (8 * 0)) & 0xFF; 00136 *(outbuffer + offset + 1) = (u_l_z.base >> (8 * 1)) & 0xFF; 00137 *(outbuffer + offset + 2) = (u_l_z.base >> (8 * 2)) & 0xFF; 00138 *(outbuffer + offset + 3) = (u_l_z.base >> (8 * 3)) & 0xFF; 00139 *(outbuffer + offset + 4) = (u_l_z.base >> (8 * 4)) & 0xFF; 00140 *(outbuffer + offset + 5) = (u_l_z.base >> (8 * 5)) & 0xFF; 00141 *(outbuffer + offset + 6) = (u_l_z.base >> (8 * 6)) & 0xFF; 00142 *(outbuffer + offset + 7) = (u_l_z.base >> (8 * 7)) & 0xFF; 00143 offset += sizeof(this->l_z); 00144 return offset; 00145 } 00146 00147 virtual int deserialize(unsigned char *inbuffer) 00148 { 00149 int offset = 0; 00150 union { 00151 double real; 00152 uint64_t base; 00153 } u_x; 00154 u_x.base = 0; 00155 u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00156 u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00157 u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00158 u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00159 u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00160 u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00161 u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00162 u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00163 this->x = u_x.real; 00164 offset += sizeof(this->x); 00165 union { 00166 double real; 00167 uint64_t base; 00168 } u_y; 00169 u_y.base = 0; 00170 u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00171 u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00172 u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00173 u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00174 u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00175 u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00176 u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00177 u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00178 this->y = u_y.real; 00179 offset += sizeof(this->y); 00180 union { 00181 double real; 00182 uint64_t base; 00183 } u_z; 00184 u_z.base = 0; 00185 u_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00186 u_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00187 u_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00188 u_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00189 u_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00190 u_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00191 u_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00192 u_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00193 this->z = u_z.real; 00194 offset += sizeof(this->z); 00195 union { 00196 double real; 00197 uint64_t base; 00198 } u_r; 00199 u_r.base = 0; 00200 u_r.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00201 u_r.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00202 u_r.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00203 u_r.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00204 u_r.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00205 u_r.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00206 u_r.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00207 u_r.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00208 this->r = u_r.real; 00209 offset += sizeof(this->r); 00210 union { 00211 double real; 00212 uint64_t base; 00213 } u_l_x; 00214 u_l_x.base = 0; 00215 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00216 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00217 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00218 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00219 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00220 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00221 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00222 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00223 this->l_x = u_l_x.real; 00224 offset += sizeof(this->l_x); 00225 union { 00226 double real; 00227 uint64_t base; 00228 } u_l_y; 00229 u_l_y.base = 0; 00230 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00231 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00232 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00233 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00234 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00235 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00236 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00237 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00238 this->l_y = u_l_y.real; 00239 offset += sizeof(this->l_y); 00240 union { 00241 double real; 00242 uint64_t base; 00243 } u_l_z; 00244 u_l_z.base = 0; 00245 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00246 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00247 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00248 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00249 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00250 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00251 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00252 u_l_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00253 this->l_z = u_l_z.real; 00254 offset += sizeof(this->l_z); 00255 return offset; 00256 } 00257 00258 const char * getType(){ return GETPOINTMAPROI; }; 00259 const char * getMD5(){ return "895f7e437a9a6dd225316872b187a303"; }; 00260 00261 }; 00262 00263 class GetPointMapROIResponse : public ros::Msg 00264 { 00265 public: 00266 typedef sensor_msgs::PointCloud2 _sub_map_type; 00267 _sub_map_type sub_map; 00268 00269 GetPointMapROIResponse(): 00270 sub_map() 00271 { 00272 } 00273 00274 virtual int serialize(unsigned char *outbuffer) const 00275 { 00276 int offset = 0; 00277 offset += this->sub_map.serialize(outbuffer + offset); 00278 return offset; 00279 } 00280 00281 virtual int deserialize(unsigned char *inbuffer) 00282 { 00283 int offset = 0; 00284 offset += this->sub_map.deserialize(inbuffer + offset); 00285 return offset; 00286 } 00287 00288 const char * getType(){ return GETPOINTMAPROI; }; 00289 const char * getMD5(){ return "313769f8b0e724525c6463336cbccd63"; }; 00290 00291 }; 00292 00293 class GetPointMapROI { 00294 public: 00295 typedef GetPointMapROIRequest Request; 00296 typedef GetPointMapROIResponse Response; 00297 }; 00298 00299 } 00300 #endif
Generated on Tue Jul 12 2022 18:49:18 by 1.7.2