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.
Dependents: rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more
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 std_msgs::Header header; 00018 nav_msgs::MapMetaData info; 00019 uint8_t data_length; 00020 int8_t st_data; 00021 int8_t * data; 00022 00023 OccupancyGrid(): 00024 header(), 00025 info(), 00026 data_length(0), data(NULL) 00027 { 00028 } 00029 00030 virtual int serialize(unsigned char *outbuffer) const 00031 { 00032 int offset = 0; 00033 offset += this->header.serialize(outbuffer + offset); 00034 offset += this->info.serialize(outbuffer + offset); 00035 *(outbuffer + offset++) = data_length; 00036 *(outbuffer + offset++) = 0; 00037 *(outbuffer + offset++) = 0; 00038 *(outbuffer + offset++) = 0; 00039 for( uint8_t i = 0; i < data_length; i++){ 00040 union { 00041 int8_t real; 00042 uint8_t base; 00043 } u_datai; 00044 u_datai.real = this->data[i]; 00045 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; 00046 offset += sizeof(this->data[i]); 00047 } 00048 return offset; 00049 } 00050 00051 virtual int deserialize(unsigned char *inbuffer) 00052 { 00053 int offset = 0; 00054 offset += this->header.deserialize(inbuffer + offset); 00055 offset += this->info.deserialize(inbuffer + offset); 00056 uint8_t data_lengthT = *(inbuffer + offset++); 00057 if(data_lengthT > data_length) 00058 this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); 00059 offset += 3; 00060 data_length = data_lengthT; 00061 for( uint8_t i = 0; i < data_length; i++){ 00062 union { 00063 int8_t real; 00064 uint8_t base; 00065 } u_st_data; 00066 u_st_data.base = 0; 00067 u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00068 this->st_data = u_st_data.real; 00069 offset += sizeof(this->st_data); 00070 memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); 00071 } 00072 return offset; 00073 } 00074 00075 const char * getType(){ return "nav_msgs/OccupancyGrid"; }; 00076 const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; }; 00077 00078 }; 00079 00080 } 00081 #endif
Generated on Tue Jul 12 2022 18:39:40 by
1.7.2