Irfan Tito Kurniawan / ros_lib
Committer:
irfantitok
Date:
Wed Sep 02 13:51:31 2020 +0000
Revision:
0:8f3710bfd298
Resolved round not found

Who changed what in which revision?

UserRevisionLine numberNew contents of line
irfantitok 0:8f3710bfd298 1 #ifndef _ROS_SERVICE_UpdateGeographicMap_h
irfantitok 0:8f3710bfd298 2 #define _ROS_SERVICE_UpdateGeographicMap_h
irfantitok 0:8f3710bfd298 3 #include <stdint.h>
irfantitok 0:8f3710bfd298 4 #include <string.h>
irfantitok 0:8f3710bfd298 5 #include <stdlib.h>
irfantitok 0:8f3710bfd298 6 #include "ros/msg.h"
irfantitok 0:8f3710bfd298 7 #include "geographic_msgs/GeographicMapChanges.h"
irfantitok 0:8f3710bfd298 8
irfantitok 0:8f3710bfd298 9 namespace geographic_msgs
irfantitok 0:8f3710bfd298 10 {
irfantitok 0:8f3710bfd298 11
irfantitok 0:8f3710bfd298 12 static const char UPDATEGEOGRAPHICMAP[] = "geographic_msgs/UpdateGeographicMap";
irfantitok 0:8f3710bfd298 13
irfantitok 0:8f3710bfd298 14 class UpdateGeographicMapRequest : public ros::Msg
irfantitok 0:8f3710bfd298 15 {
irfantitok 0:8f3710bfd298 16 public:
irfantitok 0:8f3710bfd298 17 typedef geographic_msgs::GeographicMapChanges _updates_type;
irfantitok 0:8f3710bfd298 18 _updates_type updates;
irfantitok 0:8f3710bfd298 19
irfantitok 0:8f3710bfd298 20 UpdateGeographicMapRequest():
irfantitok 0:8f3710bfd298 21 updates()
irfantitok 0:8f3710bfd298 22 {
irfantitok 0:8f3710bfd298 23 }
irfantitok 0:8f3710bfd298 24
irfantitok 0:8f3710bfd298 25 virtual int serialize(unsigned char *outbuffer) const
irfantitok 0:8f3710bfd298 26 {
irfantitok 0:8f3710bfd298 27 int offset = 0;
irfantitok 0:8f3710bfd298 28 offset += this->updates.serialize(outbuffer + offset);
irfantitok 0:8f3710bfd298 29 return offset;
irfantitok 0:8f3710bfd298 30 }
irfantitok 0:8f3710bfd298 31
irfantitok 0:8f3710bfd298 32 virtual int deserialize(unsigned char *inbuffer)
irfantitok 0:8f3710bfd298 33 {
irfantitok 0:8f3710bfd298 34 int offset = 0;
irfantitok 0:8f3710bfd298 35 offset += this->updates.deserialize(inbuffer + offset);
irfantitok 0:8f3710bfd298 36 return offset;
irfantitok 0:8f3710bfd298 37 }
irfantitok 0:8f3710bfd298 38
irfantitok 0:8f3710bfd298 39 const char * getType(){ return UPDATEGEOGRAPHICMAP; };
irfantitok 0:8f3710bfd298 40 const char * getMD5(){ return "8d8da723a1fadc5f7621a18b4e72fc3b"; };
irfantitok 0:8f3710bfd298 41
irfantitok 0:8f3710bfd298 42 };
irfantitok 0:8f3710bfd298 43
irfantitok 0:8f3710bfd298 44 class UpdateGeographicMapResponse : public ros::Msg
irfantitok 0:8f3710bfd298 45 {
irfantitok 0:8f3710bfd298 46 public:
irfantitok 0:8f3710bfd298 47 typedef bool _success_type;
irfantitok 0:8f3710bfd298 48 _success_type success;
irfantitok 0:8f3710bfd298 49 typedef const char* _status_type;
irfantitok 0:8f3710bfd298 50 _status_type status;
irfantitok 0:8f3710bfd298 51
irfantitok 0:8f3710bfd298 52 UpdateGeographicMapResponse():
irfantitok 0:8f3710bfd298 53 success(0),
irfantitok 0:8f3710bfd298 54 status("")
irfantitok 0:8f3710bfd298 55 {
irfantitok 0:8f3710bfd298 56 }
irfantitok 0:8f3710bfd298 57
irfantitok 0:8f3710bfd298 58 virtual int serialize(unsigned char *outbuffer) const
irfantitok 0:8f3710bfd298 59 {
irfantitok 0:8f3710bfd298 60 int offset = 0;
irfantitok 0:8f3710bfd298 61 union {
irfantitok 0:8f3710bfd298 62 bool real;
irfantitok 0:8f3710bfd298 63 uint8_t base;
irfantitok 0:8f3710bfd298 64 } u_success;
irfantitok 0:8f3710bfd298 65 u_success.real = this->success;
irfantitok 0:8f3710bfd298 66 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
irfantitok 0:8f3710bfd298 67 offset += sizeof(this->success);
irfantitok 0:8f3710bfd298 68 uint32_t length_status = strlen(this->status);
irfantitok 0:8f3710bfd298 69 varToArr(outbuffer + offset, length_status);
irfantitok 0:8f3710bfd298 70 offset += 4;
irfantitok 0:8f3710bfd298 71 memcpy(outbuffer + offset, this->status, length_status);
irfantitok 0:8f3710bfd298 72 offset += length_status;
irfantitok 0:8f3710bfd298 73 return offset;
irfantitok 0:8f3710bfd298 74 }
irfantitok 0:8f3710bfd298 75
irfantitok 0:8f3710bfd298 76 virtual int deserialize(unsigned char *inbuffer)
irfantitok 0:8f3710bfd298 77 {
irfantitok 0:8f3710bfd298 78 int offset = 0;
irfantitok 0:8f3710bfd298 79 union {
irfantitok 0:8f3710bfd298 80 bool real;
irfantitok 0:8f3710bfd298 81 uint8_t base;
irfantitok 0:8f3710bfd298 82 } u_success;
irfantitok 0:8f3710bfd298 83 u_success.base = 0;
irfantitok 0:8f3710bfd298 84 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
irfantitok 0:8f3710bfd298 85 this->success = u_success.real;
irfantitok 0:8f3710bfd298 86 offset += sizeof(this->success);
irfantitok 0:8f3710bfd298 87 uint32_t length_status;
irfantitok 0:8f3710bfd298 88 arrToVar(length_status, (inbuffer + offset));
irfantitok 0:8f3710bfd298 89 offset += 4;
irfantitok 0:8f3710bfd298 90 for(unsigned int k= offset; k< offset+length_status; ++k){
irfantitok 0:8f3710bfd298 91 inbuffer[k-1]=inbuffer[k];
irfantitok 0:8f3710bfd298 92 }
irfantitok 0:8f3710bfd298 93 inbuffer[offset+length_status-1]=0;
irfantitok 0:8f3710bfd298 94 this->status = (char *)(inbuffer + offset-1);
irfantitok 0:8f3710bfd298 95 offset += length_status;
irfantitok 0:8f3710bfd298 96 return offset;
irfantitok 0:8f3710bfd298 97 }
irfantitok 0:8f3710bfd298 98
irfantitok 0:8f3710bfd298 99 const char * getType(){ return UPDATEGEOGRAPHICMAP; };
irfantitok 0:8f3710bfd298 100 const char * getMD5(){ return "38b8954d32a849f31d78416b12bff5d1"; };
irfantitok 0:8f3710bfd298 101
irfantitok 0:8f3710bfd298 102 };
irfantitok 0:8f3710bfd298 103
irfantitok 0:8f3710bfd298 104 class UpdateGeographicMap {
irfantitok 0:8f3710bfd298 105 public:
irfantitok 0:8f3710bfd298 106 typedef UpdateGeographicMapRequest Request;
irfantitok 0:8f3710bfd298 107 typedef UpdateGeographicMapResponse Response;
irfantitok 0:8f3710bfd298 108 };
irfantitok 0:8f3710bfd298 109
irfantitok 0:8f3710bfd298 110 }
irfantitok 0:8f3710bfd298 111 #endif