Go to the documentation of this file.00001 #ifndef _ROS_pcl_msgs_Vertices_h
00002 #define _ROS_pcl_msgs_Vertices_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008
00009 namespace pcl_msgs
00010 {
00011
00012 class Vertices : public ros::Msg
00013 {
00014 public:
00015 uint8_t vertices_length;
00016 uint32_t st_vertices;
00017 uint32_t * vertices;
00018
00019 virtual int serialize(unsigned char *outbuffer) const
00020 {
00021 int offset = 0;
00022 *(outbuffer + offset++) = vertices_length;
00023 *(outbuffer + offset++) = 0;
00024 *(outbuffer + offset++) = 0;
00025 *(outbuffer + offset++) = 0;
00026 for( uint8_t i = 0; i < vertices_length; i++){
00027 *(outbuffer + offset + 0) = (this->vertices[i] >> (8 * 0)) & 0xFF;
00028 *(outbuffer + offset + 1) = (this->vertices[i] >> (8 * 1)) & 0xFF;
00029 *(outbuffer + offset + 2) = (this->vertices[i] >> (8 * 2)) & 0xFF;
00030 *(outbuffer + offset + 3) = (this->vertices[i] >> (8 * 3)) & 0xFF;
00031 offset += sizeof(this->vertices[i]);
00032 }
00033 return offset;
00034 }
00035
00036 virtual int deserialize(unsigned char *inbuffer)
00037 {
00038 int offset = 0;
00039 uint8_t vertices_lengthT = *(inbuffer + offset++);
00040 if(vertices_lengthT > vertices_length)
00041 this->vertices = (uint32_t*)realloc(this->vertices, vertices_lengthT * sizeof(uint32_t));
00042 offset += 3;
00043 vertices_length = vertices_lengthT;
00044 for( uint8_t i = 0; i < vertices_length; i++){
00045 this->st_vertices = ((uint32_t) (*(inbuffer + offset)));
00046 this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00047 this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00048 this->st_vertices |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00049 offset += sizeof(this->st_vertices);
00050 memcpy( &(this->vertices[i]), &(this->st_vertices), sizeof(uint32_t));
00051 }
00052 return offset;
00053 }
00054
00055 const char * getType(){ return "pcl_msgs/Vertices"; };
00056 const char * getMD5(){ return "39bd7b1c23763ddd1b882b97cb7cfe11"; };
00057
00058 };
00059
00060 }
00061 #endif