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.
SetMap.h
00001 #ifndef _ROS_SERVICE_SetMap_h 00002 #define _ROS_SERVICE_SetMap_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 #include "geometry_msgs/PoseWithCovarianceStamped.h" 00009 00010 namespace nav_msgs 00011 { 00012 00013 static const char SETMAP[] = "nav_msgs/SetMap"; 00014 00015 class SetMapRequest : public ros::Msg 00016 { 00017 public: 00018 typedef nav_msgs::OccupancyGrid _map_type; 00019 _map_type map; 00020 typedef geometry_msgs::PoseWithCovarianceStamped _initial_pose_type; 00021 _initial_pose_type initial_pose; 00022 00023 SetMapRequest(): 00024 map(), 00025 initial_pose() 00026 { 00027 } 00028 00029 virtual int serialize(unsigned char *outbuffer) const 00030 { 00031 int offset = 0; 00032 offset += this->map.serialize(outbuffer + offset); 00033 offset += this->initial_pose.serialize(outbuffer + offset); 00034 return offset; 00035 } 00036 00037 virtual int deserialize(unsigned char *inbuffer) 00038 { 00039 int offset = 0; 00040 offset += this->map.deserialize(inbuffer + offset); 00041 offset += this->initial_pose.deserialize(inbuffer + offset); 00042 return offset; 00043 } 00044 00045 const char * getType(){ return SETMAP; }; 00046 const char * getMD5(){ return "91149a20d7be299b87c340df8cc94fd4"; }; 00047 00048 }; 00049 00050 class SetMapResponse : public ros::Msg 00051 { 00052 public: 00053 typedef bool _success_type; 00054 _success_type success; 00055 00056 SetMapResponse(): 00057 success(0) 00058 { 00059 } 00060 00061 virtual int serialize(unsigned char *outbuffer) const 00062 { 00063 int offset = 0; 00064 union { 00065 bool real; 00066 uint8_t base; 00067 } u_success; 00068 u_success.real = this->success; 00069 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; 00070 offset += sizeof(this->success); 00071 return offset; 00072 } 00073 00074 virtual int deserialize(unsigned char *inbuffer) 00075 { 00076 int offset = 0; 00077 union { 00078 bool real; 00079 uint8_t base; 00080 } u_success; 00081 u_success.base = 0; 00082 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00083 this->success = u_success.real; 00084 offset += sizeof(this->success); 00085 return offset; 00086 } 00087 00088 const char * getType(){ return SETMAP; }; 00089 const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; 00090 00091 }; 00092 00093 class SetMap { 00094 public: 00095 typedef SetMapRequest Request; 00096 typedef SetMapResponse Response; 00097 }; 00098 00099 } 00100 #endif
Generated on Wed Jul 13 2022 23:30:18 by
