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.
PointCloud.h
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 typedef std_msgs::Header _header_type; 00019 _header_type header; 00020 uint32_t points_length; 00021 typedef geometry_msgs::Point32 _points_type; 00022 _points_type st_points; 00023 _points_type * points; 00024 uint32_t channels_length; 00025 typedef sensor_msgs::ChannelFloat32 _channels_type; 00026 _channels_type st_channels; 00027 _channels_type * channels; 00028 00029 PointCloud(): 00030 header(), 00031 points_length(0), points(NULL), 00032 channels_length(0), channels(NULL) 00033 { 00034 } 00035 00036 virtual int serialize(unsigned char *outbuffer) const 00037 { 00038 int offset = 0; 00039 offset += this->header.serialize(outbuffer + offset); 00040 *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF; 00041 *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF; 00042 *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF; 00043 *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF; 00044 offset += sizeof(this->points_length); 00045 for( uint32_t i = 0; i < points_length; i++){ 00046 offset += this->points[i].serialize(outbuffer + offset); 00047 } 00048 *(outbuffer + offset + 0) = (this->channels_length >> (8 * 0)) & 0xFF; 00049 *(outbuffer + offset + 1) = (this->channels_length >> (8 * 1)) & 0xFF; 00050 *(outbuffer + offset + 2) = (this->channels_length >> (8 * 2)) & 0xFF; 00051 *(outbuffer + offset + 3) = (this->channels_length >> (8 * 3)) & 0xFF; 00052 offset += sizeof(this->channels_length); 00053 for( uint32_t i = 0; i < channels_length; i++){ 00054 offset += this->channels[i].serialize(outbuffer + offset); 00055 } 00056 return offset; 00057 } 00058 00059 virtual int deserialize(unsigned char *inbuffer) 00060 { 00061 int offset = 0; 00062 offset += this->header.deserialize(inbuffer + offset); 00063 uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 00064 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00065 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00066 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00067 offset += sizeof(this->points_length); 00068 if(points_lengthT > points_length) 00069 this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32)); 00070 points_length = points_lengthT; 00071 for( uint32_t i = 0; i < points_length; i++){ 00072 offset += this->st_points.deserialize(inbuffer + offset); 00073 memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32)); 00074 } 00075 uint32_t channels_lengthT = ((uint32_t) (*(inbuffer + offset))); 00076 channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00077 channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00078 channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00079 offset += sizeof(this->channels_length); 00080 if(channels_lengthT > channels_length) 00081 this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32)); 00082 channels_length = channels_lengthT; 00083 for( uint32_t i = 0; i < channels_length; i++){ 00084 offset += this->st_channels.deserialize(inbuffer + offset); 00085 memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32)); 00086 } 00087 return offset; 00088 } 00089 00090 const char * getType(){ return "sensor_msgs/PointCloud"; }; 00091 const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; }; 00092 00093 }; 00094 00095 } 00096 #endif
Generated on Tue Jul 12 2022 17:32:45 by
