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.
ProjectedMapsInfo.h
00001 #ifndef _ROS_SERVICE_ProjectedMapsInfo_h 00002 #define _ROS_SERVICE_ProjectedMapsInfo_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "map_msgs/ProjectedMapInfo.h" 00008 00009 namespace map_msgs 00010 { 00011 00012 static const char PROJECTEDMAPSINFO[] = "map_msgs/ProjectedMapsInfo"; 00013 00014 class ProjectedMapsInfoRequest : public ros::Msg 00015 { 00016 public: 00017 uint32_t projected_maps_info_length; 00018 typedef map_msgs::ProjectedMapInfo _projected_maps_info_type; 00019 _projected_maps_info_type st_projected_maps_info; 00020 _projected_maps_info_type * projected_maps_info; 00021 00022 ProjectedMapsInfoRequest(): 00023 projected_maps_info_length(0), projected_maps_info(NULL) 00024 { 00025 } 00026 00027 virtual int serialize(unsigned char *outbuffer) const 00028 { 00029 int offset = 0; 00030 *(outbuffer + offset + 0) = (this->projected_maps_info_length >> (8 * 0)) & 0xFF; 00031 *(outbuffer + offset + 1) = (this->projected_maps_info_length >> (8 * 1)) & 0xFF; 00032 *(outbuffer + offset + 2) = (this->projected_maps_info_length >> (8 * 2)) & 0xFF; 00033 *(outbuffer + offset + 3) = (this->projected_maps_info_length >> (8 * 3)) & 0xFF; 00034 offset += sizeof(this->projected_maps_info_length); 00035 for( uint32_t i = 0; i < projected_maps_info_length; i++){ 00036 offset += this->projected_maps_info[i].serialize(outbuffer + offset); 00037 } 00038 return offset; 00039 } 00040 00041 virtual int deserialize(unsigned char *inbuffer) 00042 { 00043 int offset = 0; 00044 uint32_t projected_maps_info_lengthT = ((uint32_t) (*(inbuffer + offset))); 00045 projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00046 projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00047 projected_maps_info_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00048 offset += sizeof(this->projected_maps_info_length); 00049 if(projected_maps_info_lengthT > projected_maps_info_length) 00050 this->projected_maps_info = (map_msgs::ProjectedMapInfo*)realloc(this->projected_maps_info, projected_maps_info_lengthT * sizeof(map_msgs::ProjectedMapInfo)); 00051 projected_maps_info_length = projected_maps_info_lengthT; 00052 for( uint32_t i = 0; i < projected_maps_info_length; i++){ 00053 offset += this->st_projected_maps_info.deserialize(inbuffer + offset); 00054 memcpy( &(this->projected_maps_info[i]), &(this->st_projected_maps_info), sizeof(map_msgs::ProjectedMapInfo)); 00055 } 00056 return offset; 00057 } 00058 00059 const char * getType(){ return PROJECTEDMAPSINFO; }; 00060 const char * getMD5(){ return "d7980a33202421c8cd74565e57a4d229"; }; 00061 00062 }; 00063 00064 class ProjectedMapsInfoResponse : public ros::Msg 00065 { 00066 public: 00067 00068 ProjectedMapsInfoResponse() 00069 { 00070 } 00071 00072 virtual int serialize(unsigned char *outbuffer) const 00073 { 00074 int offset = 0; 00075 return offset; 00076 } 00077 00078 virtual int deserialize(unsigned char *inbuffer) 00079 { 00080 int offset = 0; 00081 return offset; 00082 } 00083 00084 const char * getType(){ return PROJECTEDMAPSINFO; }; 00085 const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; }; 00086 00087 }; 00088 00089 class ProjectedMapsInfo { 00090 public: 00091 typedef ProjectedMapsInfoRequest Request; 00092 typedef ProjectedMapsInfoResponse Response; 00093 }; 00094 00095 } 00096 #endif
Generated on Tue Jul 12 2022 17:32:45 by
