Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers GetMapROI.h Source File

GetMapROI.h

00001 #ifndef _ROS_SERVICE_GetMapROI_h
00002 #define _ROS_SERVICE_GetMapROI_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "nav_msgs/OccupancyGrid.h"
00008 
00009 namespace map_msgs
00010 {
00011 
00012 static const char GETMAPROI[] = "map_msgs/GetMapROI";
00013 
00014   class GetMapROIRequest : 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 _l_x_type;
00022       _l_x_type l_x;
00023       typedef double _l_y_type;
00024       _l_y_type l_y;
00025 
00026     GetMapROIRequest():
00027       x(0),
00028       y(0),
00029       l_x(0),
00030       l_y(0)
00031     {
00032     }
00033 
00034     virtual int serialize(unsigned char *outbuffer) const
00035     {
00036       int offset = 0;
00037       union {
00038         double real;
00039         uint64_t base;
00040       } u_x;
00041       u_x.real = this->x;
00042       *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
00043       *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
00044       *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
00045       *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
00046       *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
00047       *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
00048       *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
00049       *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
00050       offset += sizeof(this->x);
00051       union {
00052         double real;
00053         uint64_t base;
00054       } u_y;
00055       u_y.real = this->y;
00056       *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
00057       *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
00058       *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
00059       *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
00060       *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
00061       *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
00062       *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
00063       *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
00064       offset += sizeof(this->y);
00065       union {
00066         double real;
00067         uint64_t base;
00068       } u_l_x;
00069       u_l_x.real = this->l_x;
00070       *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF;
00071       *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF;
00072       *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF;
00073       *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF;
00074       *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF;
00075       *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF;
00076       *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF;
00077       *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF;
00078       offset += sizeof(this->l_x);
00079       union {
00080         double real;
00081         uint64_t base;
00082       } u_l_y;
00083       u_l_y.real = this->l_y;
00084       *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF;
00085       *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF;
00086       *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF;
00087       *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF;
00088       *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF;
00089       *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF;
00090       *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF;
00091       *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF;
00092       offset += sizeof(this->l_y);
00093       return offset;
00094     }
00095 
00096     virtual int deserialize(unsigned char *inbuffer)
00097     {
00098       int offset = 0;
00099       union {
00100         double real;
00101         uint64_t base;
00102       } u_x;
00103       u_x.base = 0;
00104       u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00105       u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00106       u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00107       u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00108       u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00109       u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00110       u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00111       u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00112       this->x = u_x.real;
00113       offset += sizeof(this->x);
00114       union {
00115         double real;
00116         uint64_t base;
00117       } u_y;
00118       u_y.base = 0;
00119       u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00120       u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00121       u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00122       u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00123       u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00124       u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00125       u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00126       u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00127       this->y = u_y.real;
00128       offset += sizeof(this->y);
00129       union {
00130         double real;
00131         uint64_t base;
00132       } u_l_x;
00133       u_l_x.base = 0;
00134       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00135       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00136       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00137       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00138       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00139       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00140       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00141       u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00142       this->l_x = u_l_x.real;
00143       offset += sizeof(this->l_x);
00144       union {
00145         double real;
00146         uint64_t base;
00147       } u_l_y;
00148       u_l_y.base = 0;
00149       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00150       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00151       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00152       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00153       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00154       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00155       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00156       u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00157       this->l_y = u_l_y.real;
00158       offset += sizeof(this->l_y);
00159      return offset;
00160     }
00161 
00162     const char * getType(){ return GETMAPROI; };
00163     const char * getMD5(){ return "43c2ff8f45af555c0eaf070c401e9a47"; };
00164 
00165   };
00166 
00167   class GetMapROIResponse : public ros::Msg
00168   {
00169     public:
00170       typedef nav_msgs::OccupancyGrid _sub_map_type;
00171       _sub_map_type sub_map;
00172 
00173     GetMapROIResponse():
00174       sub_map()
00175     {
00176     }
00177 
00178     virtual int serialize(unsigned char *outbuffer) const
00179     {
00180       int offset = 0;
00181       offset += this->sub_map.serialize(outbuffer + offset);
00182       return offset;
00183     }
00184 
00185     virtual int deserialize(unsigned char *inbuffer)
00186     {
00187       int offset = 0;
00188       offset += this->sub_map.deserialize(inbuffer + offset);
00189      return offset;
00190     }
00191 
00192     const char * getType(){ return GETMAPROI; };
00193     const char * getMD5(){ return "4d1986519c00d81967d2891a606b234c"; };
00194 
00195   };
00196 
00197   class GetMapROI {
00198     public:
00199     typedef GetMapROIRequest Request;
00200     typedef GetMapROIResponse Response;
00201   };
00202 
00203 }
00204 #endif