ros melodic library with custom message

Dependents:   Robot_team1_QEI_Douglas Robot_team1

Committer:
scarter1
Date:
Wed Oct 30 14:59:49 2019 +0000
Revision:
0:020db18a476d
melodic library;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
scarter1 0:020db18a476d 1 #ifndef _ROS_SERVICE_GetMapROI_h
scarter1 0:020db18a476d 2 #define _ROS_SERVICE_GetMapROI_h
scarter1 0:020db18a476d 3 #include <stdint.h>
scarter1 0:020db18a476d 4 #include <string.h>
scarter1 0:020db18a476d 5 #include <stdlib.h>
scarter1 0:020db18a476d 6 #include "ros/msg.h"
scarter1 0:020db18a476d 7 #include "nav_msgs/OccupancyGrid.h"
scarter1 0:020db18a476d 8
scarter1 0:020db18a476d 9 namespace map_msgs
scarter1 0:020db18a476d 10 {
scarter1 0:020db18a476d 11
scarter1 0:020db18a476d 12 static const char GETMAPROI[] = "map_msgs/GetMapROI";
scarter1 0:020db18a476d 13
scarter1 0:020db18a476d 14 class GetMapROIRequest : public ros::Msg
scarter1 0:020db18a476d 15 {
scarter1 0:020db18a476d 16 public:
scarter1 0:020db18a476d 17 typedef double _x_type;
scarter1 0:020db18a476d 18 _x_type x;
scarter1 0:020db18a476d 19 typedef double _y_type;
scarter1 0:020db18a476d 20 _y_type y;
scarter1 0:020db18a476d 21 typedef double _l_x_type;
scarter1 0:020db18a476d 22 _l_x_type l_x;
scarter1 0:020db18a476d 23 typedef double _l_y_type;
scarter1 0:020db18a476d 24 _l_y_type l_y;
scarter1 0:020db18a476d 25
scarter1 0:020db18a476d 26 GetMapROIRequest():
scarter1 0:020db18a476d 27 x(0),
scarter1 0:020db18a476d 28 y(0),
scarter1 0:020db18a476d 29 l_x(0),
scarter1 0:020db18a476d 30 l_y(0)
scarter1 0:020db18a476d 31 {
scarter1 0:020db18a476d 32 }
scarter1 0:020db18a476d 33
scarter1 0:020db18a476d 34 virtual int serialize(unsigned char *outbuffer) const
scarter1 0:020db18a476d 35 {
scarter1 0:020db18a476d 36 int offset = 0;
scarter1 0:020db18a476d 37 union {
scarter1 0:020db18a476d 38 double real;
scarter1 0:020db18a476d 39 uint64_t base;
scarter1 0:020db18a476d 40 } u_x;
scarter1 0:020db18a476d 41 u_x.real = this->x;
scarter1 0:020db18a476d 42 *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 43 *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 44 *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 45 *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 46 *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 47 *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 48 *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 49 *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 50 offset += sizeof(this->x);
scarter1 0:020db18a476d 51 union {
scarter1 0:020db18a476d 52 double real;
scarter1 0:020db18a476d 53 uint64_t base;
scarter1 0:020db18a476d 54 } u_y;
scarter1 0:020db18a476d 55 u_y.real = this->y;
scarter1 0:020db18a476d 56 *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 57 *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 58 *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 59 *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 60 *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 61 *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 62 *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 63 *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 64 offset += sizeof(this->y);
scarter1 0:020db18a476d 65 union {
scarter1 0:020db18a476d 66 double real;
scarter1 0:020db18a476d 67 uint64_t base;
scarter1 0:020db18a476d 68 } u_l_x;
scarter1 0:020db18a476d 69 u_l_x.real = this->l_x;
scarter1 0:020db18a476d 70 *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 71 *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 72 *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 73 *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 74 *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 75 *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 76 *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 77 *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 78 offset += sizeof(this->l_x);
scarter1 0:020db18a476d 79 union {
scarter1 0:020db18a476d 80 double real;
scarter1 0:020db18a476d 81 uint64_t base;
scarter1 0:020db18a476d 82 } u_l_y;
scarter1 0:020db18a476d 83 u_l_y.real = this->l_y;
scarter1 0:020db18a476d 84 *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF;
scarter1 0:020db18a476d 85 *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF;
scarter1 0:020db18a476d 86 *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF;
scarter1 0:020db18a476d 87 *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF;
scarter1 0:020db18a476d 88 *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF;
scarter1 0:020db18a476d 89 *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF;
scarter1 0:020db18a476d 90 *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF;
scarter1 0:020db18a476d 91 *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF;
scarter1 0:020db18a476d 92 offset += sizeof(this->l_y);
scarter1 0:020db18a476d 93 return offset;
scarter1 0:020db18a476d 94 }
scarter1 0:020db18a476d 95
scarter1 0:020db18a476d 96 virtual int deserialize(unsigned char *inbuffer)
scarter1 0:020db18a476d 97 {
scarter1 0:020db18a476d 98 int offset = 0;
scarter1 0:020db18a476d 99 union {
scarter1 0:020db18a476d 100 double real;
scarter1 0:020db18a476d 101 uint64_t base;
scarter1 0:020db18a476d 102 } u_x;
scarter1 0:020db18a476d 103 u_x.base = 0;
scarter1 0:020db18a476d 104 u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 105 u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 106 u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 107 u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 108 u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 109 u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 110 u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 111 u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 112 this->x = u_x.real;
scarter1 0:020db18a476d 113 offset += sizeof(this->x);
scarter1 0:020db18a476d 114 union {
scarter1 0:020db18a476d 115 double real;
scarter1 0:020db18a476d 116 uint64_t base;
scarter1 0:020db18a476d 117 } u_y;
scarter1 0:020db18a476d 118 u_y.base = 0;
scarter1 0:020db18a476d 119 u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 120 u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 121 u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 122 u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 123 u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 124 u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 125 u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 126 u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 127 this->y = u_y.real;
scarter1 0:020db18a476d 128 offset += sizeof(this->y);
scarter1 0:020db18a476d 129 union {
scarter1 0:020db18a476d 130 double real;
scarter1 0:020db18a476d 131 uint64_t base;
scarter1 0:020db18a476d 132 } u_l_x;
scarter1 0:020db18a476d 133 u_l_x.base = 0;
scarter1 0:020db18a476d 134 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 135 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 136 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 137 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 138 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 139 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 140 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 141 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 142 this->l_x = u_l_x.real;
scarter1 0:020db18a476d 143 offset += sizeof(this->l_x);
scarter1 0:020db18a476d 144 union {
scarter1 0:020db18a476d 145 double real;
scarter1 0:020db18a476d 146 uint64_t base;
scarter1 0:020db18a476d 147 } u_l_y;
scarter1 0:020db18a476d 148 u_l_y.base = 0;
scarter1 0:020db18a476d 149 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
scarter1 0:020db18a476d 150 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
scarter1 0:020db18a476d 151 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
scarter1 0:020db18a476d 152 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
scarter1 0:020db18a476d 153 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
scarter1 0:020db18a476d 154 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
scarter1 0:020db18a476d 155 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
scarter1 0:020db18a476d 156 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
scarter1 0:020db18a476d 157 this->l_y = u_l_y.real;
scarter1 0:020db18a476d 158 offset += sizeof(this->l_y);
scarter1 0:020db18a476d 159 return offset;
scarter1 0:020db18a476d 160 }
scarter1 0:020db18a476d 161
scarter1 0:020db18a476d 162 const char * getType(){ return GETMAPROI; };
scarter1 0:020db18a476d 163 const char * getMD5(){ return "43c2ff8f45af555c0eaf070c401e9a47"; };
scarter1 0:020db18a476d 164
scarter1 0:020db18a476d 165 };
scarter1 0:020db18a476d 166
scarter1 0:020db18a476d 167 class GetMapROIResponse : public ros::Msg
scarter1 0:020db18a476d 168 {
scarter1 0:020db18a476d 169 public:
scarter1 0:020db18a476d 170 typedef nav_msgs::OccupancyGrid _sub_map_type;
scarter1 0:020db18a476d 171 _sub_map_type sub_map;
scarter1 0:020db18a476d 172
scarter1 0:020db18a476d 173 GetMapROIResponse():
scarter1 0:020db18a476d 174 sub_map()
scarter1 0:020db18a476d 175 {
scarter1 0:020db18a476d 176 }
scarter1 0:020db18a476d 177
scarter1 0:020db18a476d 178 virtual int serialize(unsigned char *outbuffer) const
scarter1 0:020db18a476d 179 {
scarter1 0:020db18a476d 180 int offset = 0;
scarter1 0:020db18a476d 181 offset += this->sub_map.serialize(outbuffer + offset);
scarter1 0:020db18a476d 182 return offset;
scarter1 0:020db18a476d 183 }
scarter1 0:020db18a476d 184
scarter1 0:020db18a476d 185 virtual int deserialize(unsigned char *inbuffer)
scarter1 0:020db18a476d 186 {
scarter1 0:020db18a476d 187 int offset = 0;
scarter1 0:020db18a476d 188 offset += this->sub_map.deserialize(inbuffer + offset);
scarter1 0:020db18a476d 189 return offset;
scarter1 0:020db18a476d 190 }
scarter1 0:020db18a476d 191
scarter1 0:020db18a476d 192 const char * getType(){ return GETMAPROI; };
scarter1 0:020db18a476d 193 const char * getMD5(){ return "4d1986519c00d81967d2891a606b234c"; };
scarter1 0:020db18a476d 194
scarter1 0:020db18a476d 195 };
scarter1 0:020db18a476d 196
scarter1 0:020db18a476d 197 class GetMapROI {
scarter1 0:020db18a476d 198 public:
scarter1 0:020db18a476d 199 typedef GetMapROIRequest Request;
scarter1 0:020db18a476d 200 typedef GetMapROIResponse Response;
scarter1 0:020db18a476d 201 };
scarter1 0:020db18a476d 202
scarter1 0:020db18a476d 203 }
scarter1 0:020db18a476d 204 #endif