ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
Dependents: rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more
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 double x; 00018 double y; 00019 double l_x; 00020 double l_y; 00021 00022 GetMapROIRequest(): 00023 x(0), 00024 y(0), 00025 l_x(0), 00026 l_y(0) 00027 { 00028 } 00029 00030 virtual int serialize(unsigned char *outbuffer) const 00031 { 00032 int offset = 0; 00033 union { 00034 double real; 00035 uint64_t base; 00036 } u_x; 00037 u_x.real = this->x; 00038 *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; 00039 *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; 00040 *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; 00041 *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; 00042 *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF; 00043 *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF; 00044 *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF; 00045 *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF; 00046 offset += sizeof(this->x); 00047 union { 00048 double real; 00049 uint64_t base; 00050 } u_y; 00051 u_y.real = this->y; 00052 *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; 00053 *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; 00054 *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; 00055 *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; 00056 *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF; 00057 *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF; 00058 *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF; 00059 *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF; 00060 offset += sizeof(this->y); 00061 union { 00062 double real; 00063 uint64_t base; 00064 } u_l_x; 00065 u_l_x.real = this->l_x; 00066 *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF; 00067 *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF; 00068 *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF; 00069 *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF; 00070 *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF; 00071 *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF; 00072 *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF; 00073 *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF; 00074 offset += sizeof(this->l_x); 00075 union { 00076 double real; 00077 uint64_t base; 00078 } u_l_y; 00079 u_l_y.real = this->l_y; 00080 *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF; 00081 *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF; 00082 *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF; 00083 *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF; 00084 *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF; 00085 *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF; 00086 *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF; 00087 *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF; 00088 offset += sizeof(this->l_y); 00089 return offset; 00090 } 00091 00092 virtual int deserialize(unsigned char *inbuffer) 00093 { 00094 int offset = 0; 00095 union { 00096 double real; 00097 uint64_t base; 00098 } u_x; 00099 u_x.base = 0; 00100 u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00101 u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00102 u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00103 u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00104 u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00105 u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00106 u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00107 u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00108 this->x = u_x.real; 00109 offset += sizeof(this->x); 00110 union { 00111 double real; 00112 uint64_t base; 00113 } u_y; 00114 u_y.base = 0; 00115 u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00116 u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00117 u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00118 u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00119 u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00120 u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00121 u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00122 u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00123 this->y = u_y.real; 00124 offset += sizeof(this->y); 00125 union { 00126 double real; 00127 uint64_t base; 00128 } u_l_x; 00129 u_l_x.base = 0; 00130 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00131 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00132 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00133 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00134 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00135 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00136 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00137 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00138 this->l_x = u_l_x.real; 00139 offset += sizeof(this->l_x); 00140 union { 00141 double real; 00142 uint64_t base; 00143 } u_l_y; 00144 u_l_y.base = 0; 00145 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00146 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00147 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00148 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00149 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00150 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00151 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00152 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00153 this->l_y = u_l_y.real; 00154 offset += sizeof(this->l_y); 00155 return offset; 00156 } 00157 00158 const char * getType(){ return GETMAPROI; }; 00159 const char * getMD5(){ return "43c2ff8f45af555c0eaf070c401e9a47"; }; 00160 00161 }; 00162 00163 class GetMapROIResponse : public ros::Msg 00164 { 00165 public: 00166 nav_msgs::OccupancyGrid sub_map; 00167 00168 GetMapROIResponse(): 00169 sub_map() 00170 { 00171 } 00172 00173 virtual int serialize(unsigned char *outbuffer) const 00174 { 00175 int offset = 0; 00176 offset += this->sub_map.serialize(outbuffer + offset); 00177 return offset; 00178 } 00179 00180 virtual int deserialize(unsigned char *inbuffer) 00181 { 00182 int offset = 0; 00183 offset += this->sub_map.deserialize(inbuffer + offset); 00184 return offset; 00185 } 00186 00187 const char * getType(){ return GETMAPROI; }; 00188 const char * getMD5(){ return "4d1986519c00d81967d2891a606b234c"; }; 00189 00190 }; 00191 00192 class GetMapROI { 00193 public: 00194 typedef GetMapROIRequest Request; 00195 typedef GetMapROIResponse Response; 00196 }; 00197 00198 } 00199 #endif
Generated on Tue Jul 12 2022 18:39:39 by 1.7.2