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
SaveMap.h
00001 #ifndef _ROS_SERVICE_SaveMap_h 00002 #define _ROS_SERVICE_SaveMap_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 00008 namespace moveit_msgs 00009 { 00010 00011 static const char SAVEMAP[] = "moveit_msgs/SaveMap"; 00012 00013 class SaveMapRequest : public ros::Msg 00014 { 00015 public: 00016 typedef const char* _filename_type; 00017 _filename_type filename; 00018 00019 SaveMapRequest(): 00020 filename("") 00021 { 00022 } 00023 00024 virtual int serialize(unsigned char *outbuffer) const 00025 { 00026 int offset = 0; 00027 uint32_t length_filename = strlen(this->filename); 00028 varToArr(outbuffer + offset, length_filename); 00029 offset += 4; 00030 memcpy(outbuffer + offset, this->filename, length_filename); 00031 offset += length_filename; 00032 return offset; 00033 } 00034 00035 virtual int deserialize(unsigned char *inbuffer) 00036 { 00037 int offset = 0; 00038 uint32_t length_filename; 00039 arrToVar(length_filename, (inbuffer + offset)); 00040 offset += 4; 00041 for(unsigned int k= offset; k< offset+length_filename; ++k){ 00042 inbuffer[k-1]=inbuffer[k]; 00043 } 00044 inbuffer[offset+length_filename-1]=0; 00045 this->filename = (char *)(inbuffer + offset-1); 00046 offset += length_filename; 00047 return offset; 00048 } 00049 00050 virtual const char * getType(){ return SAVEMAP; }; 00051 virtual const char * getMD5(){ return "030824f52a0628ead956fb9d67e66ae9"; }; 00052 00053 }; 00054 00055 class SaveMapResponse : public ros::Msg 00056 { 00057 public: 00058 typedef bool _success_type; 00059 _success_type success; 00060 00061 SaveMapResponse(): 00062 success(0) 00063 { 00064 } 00065 00066 virtual int serialize(unsigned char *outbuffer) const 00067 { 00068 int offset = 0; 00069 union { 00070 bool real; 00071 uint8_t base; 00072 } u_success; 00073 u_success.real = this->success; 00074 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; 00075 offset += sizeof(this->success); 00076 return offset; 00077 } 00078 00079 virtual int deserialize(unsigned char *inbuffer) 00080 { 00081 int offset = 0; 00082 union { 00083 bool real; 00084 uint8_t base; 00085 } u_success; 00086 u_success.base = 0; 00087 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00088 this->success = u_success.real; 00089 offset += sizeof(this->success); 00090 return offset; 00091 } 00092 00093 virtual const char * getType(){ return SAVEMAP; }; 00094 virtual const char * getMD5(){ return "358e233cde0c8a8bcfea4ce193f8fc15"; }; 00095 00096 }; 00097 00098 class SaveMap { 00099 public: 00100 typedef SaveMapRequest Request; 00101 typedef SaveMapResponse Response; 00102 }; 00103 00104 } 00105 #endif
Generated on Mon Sep 26 2022 13:47:03 by
