00001 #ifndef _ROS_sensor_msgs_PointCloud_h 00002 #define _ROS_sensor_msgs_PointCloud_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 "geometry_msgs/Point32.h" 00010 #include "sensor_msgs/ChannelFloat32.h" 00011 00012 namespace sensor_msgs 00013 { 00014 00015 class PointCloud : public ros::Msg 00016 { 00017 public: 00018 std_msgs::Header header; 00019 uint8_t points_length; 00020 geometry_msgs::Point32 st_points; 00021 geometry_msgs::Point32 * points; 00022 uint8_t channels_length; 00023 sensor_msgs::ChannelFloat32 st_channels; 00024 sensor_msgs::ChannelFloat32 * channels; 00025 00026 virtual int serialize(unsigned char *outbuffer) const 00027 { 00028 int offset = 0; 00029 offset += this->header.serialize(outbuffer + offset); 00030 *(outbuffer + offset++) = points_length; 00031 *(outbuffer + offset++) = 0; 00032 *(outbuffer + offset++) = 0; 00033 *(outbuffer + offset++) = 0; 00034 for( uint8_t i = 0; i < points_length; i++){ 00035 offset += this->points[i].serialize(outbuffer + offset); 00036 } 00037 *(outbuffer + offset++) = channels_length; 00038 *(outbuffer + offset++) = 0; 00039 *(outbuffer + offset++) = 0; 00040 *(outbuffer + offset++) = 0; 00041 for( uint8_t i = 0; i < channels_length; i++){ 00042 offset += this->channels[i].serialize(outbuffer + offset); 00043 } 00044 return offset; 00045 } 00046 00047 virtual int deserialize(unsigned char *inbuffer) 00048 { 00049 int offset = 0; 00050 offset += this->header.deserialize(inbuffer + offset); 00051 uint8_t points_lengthT = *(inbuffer + offset++); 00052 if(points_lengthT > points_length) 00053 this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32)); 00054 offset += 3; 00055 points_length = points_lengthT; 00056 for( uint8_t i = 0; i < points_length; i++){ 00057 offset += this->st_points.deserialize(inbuffer + offset); 00058 memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32)); 00059 } 00060 uint8_t channels_lengthT = *(inbuffer + offset++); 00061 if(channels_lengthT > channels_length) 00062 this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32)); 00063 offset += 3; 00064 channels_length = channels_lengthT; 00065 for( uint8_t i = 0; i < channels_length; i++){ 00066 offset += this->st_channels.deserialize(inbuffer + offset); 00067 memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32)); 00068 } 00069 return offset; 00070 } 00071 00072 const char * getType(){ return "sensor_msgs/PointCloud"; }; 00073 const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; }; 00074 00075 }; 00076 00077 } 00078 #endif