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.
OccupancyGrid.h
00001 #ifndef _ROS_nav_msgs_OccupancyGrid_h 00002 #define _ROS_nav_msgs_OccupancyGrid_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "std_msgs/Header.h" 00009 #include "nav_msgs/MapMetaData.h" 00010 00011 namespace nav_msgs 00012 { 00013 00014 class OccupancyGrid : public ros::Msg 00015 { 00016 public: 00017 typedef std_msgs::Header _header_type; 00018 _header_type header; 00019 typedef nav_msgs::MapMetaData _info_type; 00020 _info_type info; 00021 uint32_t data_length; 00022 typedef int8_t _data_type; 00023 _data_type st_data; 00024 _data_type * data; 00025 00026 OccupancyGrid(): 00027 header(), 00028 info(), 00029 data_length(0), data(NULL) 00030 { 00031 } 00032 00033 virtual int serialize(unsigned char *outbuffer) const 00034 { 00035 int offset = 0; 00036 offset += this->header.serialize(outbuffer + offset); 00037 offset += this->info.serialize(outbuffer + offset); 00038 *(outbuffer + offset + 0) = (this->data_length >> (8 * 0)) & 0xFF; 00039 *(outbuffer + offset + 1) = (this->data_length >> (8 * 1)) & 0xFF; 00040 *(outbuffer + offset + 2) = (this->data_length >> (8 * 2)) & 0xFF; 00041 *(outbuffer + offset + 3) = (this->data_length >> (8 * 3)) & 0xFF; 00042 offset += sizeof(this->data_length); 00043 for( uint32_t i = 0; i < data_length; i++){ 00044 union { 00045 int8_t real; 00046 uint8_t base; 00047 } u_datai; 00048 u_datai.real = this->data[i]; 00049 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; 00050 offset += sizeof(this->data[i]); 00051 } 00052 return offset; 00053 } 00054 00055 virtual int deserialize(unsigned char *inbuffer) 00056 { 00057 int offset = 0; 00058 offset += this->header.deserialize(inbuffer + offset); 00059 offset += this->info.deserialize(inbuffer + offset); 00060 uint32_t data_lengthT = ((uint32_t) (*(inbuffer + offset))); 00061 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00062 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00063 data_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00064 offset += sizeof(this->data_length); 00065 if(data_lengthT > data_length) 00066 this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); 00067 data_length = data_lengthT; 00068 for( uint32_t i = 0; i < data_length; i++){ 00069 union { 00070 int8_t real; 00071 uint8_t base; 00072 } u_st_data; 00073 u_st_data.base = 0; 00074 u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00075 this->st_data = u_st_data.real; 00076 offset += sizeof(this->st_data); 00077 memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); 00078 } 00079 return offset; 00080 } 00081 00082 const char * getType(){ return "nav_msgs/OccupancyGrid"; }; 00083 const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; }; 00084 00085 }; 00086 00087 } 00088 #endif
Generated on Tue Jul 12 2022 17:32:45 by
