ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers GetPointMapROI.h Source File

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