Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed
LoadMap.h
00001 #ifndef _ROS_SERVICE_LoadMap_h 00002 #define _ROS_SERVICE_LoadMap_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 nav_msgs 00010 { 00011 00012 static const char LOADMAP[] = "nav_msgs/LoadMap"; 00013 00014 class LoadMapRequest : public ros::Msg 00015 { 00016 public: 00017 typedef const char* _map_url_type; 00018 _map_url_type map_url; 00019 00020 LoadMapRequest(): 00021 map_url("") 00022 { 00023 } 00024 00025 virtual int serialize(unsigned char *outbuffer) const 00026 { 00027 int offset = 0; 00028 uint32_t length_map_url = strlen(this->map_url); 00029 varToArr(outbuffer + offset, length_map_url); 00030 offset += 4; 00031 memcpy(outbuffer + offset, this->map_url, length_map_url); 00032 offset += length_map_url; 00033 return offset; 00034 } 00035 00036 virtual int deserialize(unsigned char *inbuffer) 00037 { 00038 int offset = 0; 00039 uint32_t length_map_url; 00040 arrToVar(length_map_url, (inbuffer + offset)); 00041 offset += 4; 00042 for(unsigned int k= offset; k< offset+length_map_url; ++k){ 00043 inbuffer[k-1]=inbuffer[k]; 00044 } 00045 inbuffer[offset+length_map_url-1]=0; 00046 this->map_url = (char *)(inbuffer + offset-1); 00047 offset += length_map_url; 00048 return offset; 00049 } 00050 00051 virtual const char * getType(){ return LOADMAP; }; 00052 virtual const char * getMD5(){ return "3813ba1ae85fbcd4dc88c90f1426b90b"; }; 00053 00054 }; 00055 00056 class LoadMapResponse : public ros::Msg 00057 { 00058 public: 00059 typedef nav_msgs::OccupancyGrid _map_type; 00060 _map_type map; 00061 typedef uint8_t _result_type; 00062 _result_type result; 00063 enum { RESULT_SUCCESS = 0 }; 00064 enum { RESULT_MAP_DOES_NOT_EXIST = 1 }; 00065 enum { RESULT_INVALID_MAP_DATA = 2 }; 00066 enum { RESULT_INVALID_MAP_METADATA = 3 }; 00067 enum { RESULT_UNDEFINED_FAILURE = 255 }; 00068 00069 LoadMapResponse(): 00070 map(), 00071 result(0) 00072 { 00073 } 00074 00075 virtual int serialize(unsigned char *outbuffer) const 00076 { 00077 int offset = 0; 00078 offset += this->map.serialize(outbuffer + offset); 00079 *(outbuffer + offset + 0) = (this->result >> (8 * 0)) & 0xFF; 00080 offset += sizeof(this->result); 00081 return offset; 00082 } 00083 00084 virtual int deserialize(unsigned char *inbuffer) 00085 { 00086 int offset = 0; 00087 offset += this->map.deserialize(inbuffer + offset); 00088 this->result = ((uint8_t) (*(inbuffer + offset))); 00089 offset += sizeof(this->result); 00090 return offset; 00091 } 00092 00093 virtual const char * getType(){ return LOADMAP; }; 00094 virtual const char * getMD5(){ return "079b9c828e9f7c1918bf86932fd7267e"; }; 00095 00096 }; 00097 00098 class LoadMap { 00099 public: 00100 typedef LoadMapRequest Request; 00101 typedef LoadMapResponse Response; 00102 }; 00103 00104 } 00105 #endif
Generated on Mon Sep 26 2022 13:47:01 by
