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.
PolygonMesh.h
00001 #ifndef _ROS_pcl_msgs_PolygonMesh_h 00002 #define _ROS_pcl_msgs_PolygonMesh_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 "sensor_msgs/PointCloud2.h" 00010 #include "pcl_msgs/Vertices.h" 00011 00012 namespace pcl_msgs 00013 { 00014 00015 class PolygonMesh : public ros::Msg 00016 { 00017 public: 00018 typedef std_msgs::Header _header_type; 00019 _header_type header; 00020 typedef sensor_msgs::PointCloud2 _cloud_type; 00021 _cloud_type cloud; 00022 uint32_t polygons_length; 00023 typedef pcl_msgs::Vertices _polygons_type; 00024 _polygons_type st_polygons; 00025 _polygons_type * polygons; 00026 00027 PolygonMesh(): 00028 header(), 00029 cloud(), 00030 polygons_length(0), polygons(NULL) 00031 { 00032 } 00033 00034 virtual int serialize(unsigned char *outbuffer) const 00035 { 00036 int offset = 0; 00037 offset += this->header.serialize(outbuffer + offset); 00038 offset += this->cloud.serialize(outbuffer + offset); 00039 *(outbuffer + offset + 0) = (this->polygons_length >> (8 * 0)) & 0xFF; 00040 *(outbuffer + offset + 1) = (this->polygons_length >> (8 * 1)) & 0xFF; 00041 *(outbuffer + offset + 2) = (this->polygons_length >> (8 * 2)) & 0xFF; 00042 *(outbuffer + offset + 3) = (this->polygons_length >> (8 * 3)) & 0xFF; 00043 offset += sizeof(this->polygons_length); 00044 for( uint32_t i = 0; i < polygons_length; i++){ 00045 offset += this->polygons[i].serialize(outbuffer + offset); 00046 } 00047 return offset; 00048 } 00049 00050 virtual int deserialize(unsigned char *inbuffer) 00051 { 00052 int offset = 0; 00053 offset += this->header.deserialize(inbuffer + offset); 00054 offset += this->cloud.deserialize(inbuffer + offset); 00055 uint32_t polygons_lengthT = ((uint32_t) (*(inbuffer + offset))); 00056 polygons_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00057 polygons_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00058 polygons_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00059 offset += sizeof(this->polygons_length); 00060 if(polygons_lengthT > polygons_length) 00061 this->polygons = (pcl_msgs::Vertices*)realloc(this->polygons, polygons_lengthT * sizeof(pcl_msgs::Vertices)); 00062 polygons_length = polygons_lengthT; 00063 for( uint32_t i = 0; i < polygons_length; i++){ 00064 offset += this->st_polygons.deserialize(inbuffer + offset); 00065 memcpy( &(this->polygons[i]), &(this->st_polygons), sizeof(pcl_msgs::Vertices)); 00066 } 00067 return offset; 00068 } 00069 00070 const char * getType(){ return "pcl_msgs/PolygonMesh"; }; 00071 const char * getMD5(){ return "45a5fc6ad2cde8489600a790acc9a38a"; }; 00072 00073 }; 00074 00075 } 00076 #endif
Generated on Tue Jul 12 2022 17:32:45 by
