ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers PolygonMesh.h Source File

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       std_msgs::Header header;
00019       sensor_msgs::PointCloud2 cloud;
00020       uint8_t polygons_length;
00021       pcl_msgs::Vertices st_polygons;
00022       pcl_msgs::Vertices * polygons;
00023 
00024     PolygonMesh():
00025       header(),
00026       cloud(),
00027       polygons_length(0), polygons(NULL)
00028     {
00029     }
00030 
00031     virtual int serialize(unsigned char *outbuffer) const
00032     {
00033       int offset = 0;
00034       offset += this->header.serialize(outbuffer + offset);
00035       offset += this->cloud.serialize(outbuffer + offset);
00036       *(outbuffer + offset++) = polygons_length;
00037       *(outbuffer + offset++) = 0;
00038       *(outbuffer + offset++) = 0;
00039       *(outbuffer + offset++) = 0;
00040       for( uint8_t i = 0; i < polygons_length; i++){
00041       offset += this->polygons[i].serialize(outbuffer + offset);
00042       }
00043       return offset;
00044     }
00045 
00046     virtual int deserialize(unsigned char *inbuffer)
00047     {
00048       int offset = 0;
00049       offset += this->header.deserialize(inbuffer + offset);
00050       offset += this->cloud.deserialize(inbuffer + offset);
00051       uint8_t polygons_lengthT = *(inbuffer + offset++);
00052       if(polygons_lengthT > polygons_length)
00053         this->polygons = (pcl_msgs::Vertices*)realloc(this->polygons, polygons_lengthT * sizeof(pcl_msgs::Vertices));
00054       offset += 3;
00055       polygons_length = polygons_lengthT;
00056       for( uint8_t i = 0; i < polygons_length; i++){
00057       offset += this->st_polygons.deserialize(inbuffer + offset);
00058         memcpy( &(this->polygons[i]), &(this->st_polygons), sizeof(pcl_msgs::Vertices));
00059       }
00060      return offset;
00061     }
00062 
00063     const char * getType(){ return "pcl_msgs/PolygonMesh"; };
00064     const char * getMD5(){ return "45a5fc6ad2cde8489600a790acc9a38a"; };
00065 
00066   };
00067 
00068 }
00069 #endif