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.
PointField.h
00001 #ifndef _ROS_sensor_msgs_PointField_h 00002 #define _ROS_sensor_msgs_PointField_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 00009 namespace sensor_msgs 00010 { 00011 00012 class PointField : public ros::Msg 00013 { 00014 public: 00015 typedef const char* _name_type; 00016 _name_type name; 00017 typedef uint32_t _offset_type; 00018 _offset_type offset; 00019 typedef uint8_t _datatype_type; 00020 _datatype_type datatype; 00021 typedef uint32_t _count_type; 00022 _count_type count; 00023 enum { INT8 = 1 }; 00024 enum { UINT8 = 2 }; 00025 enum { INT16 = 3 }; 00026 enum { UINT16 = 4 }; 00027 enum { INT32 = 5 }; 00028 enum { UINT32 = 6 }; 00029 enum { FLOAT32 = 7 }; 00030 enum { FLOAT64 = 8 }; 00031 00032 PointField(): 00033 name(""), 00034 offset(0), 00035 datatype(0), 00036 count(0) 00037 { 00038 } 00039 00040 virtual int serialize(unsigned char *outbuffer) const 00041 { 00042 int offset = 0; 00043 uint32_t length_name = strlen(this->name); 00044 varToArr(outbuffer + offset, length_name); 00045 offset += 4; 00046 memcpy(outbuffer + offset, this->name, length_name); 00047 offset += length_name; 00048 *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF; 00049 *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF; 00050 *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF; 00051 *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF; 00052 offset += sizeof(this->offset); 00053 *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF; 00054 offset += sizeof(this->datatype); 00055 *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF; 00056 *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF; 00057 *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF; 00058 *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF; 00059 offset += sizeof(this->count); 00060 return offset; 00061 } 00062 00063 virtual int deserialize(unsigned char *inbuffer) 00064 { 00065 int offset = 0; 00066 uint32_t length_name; 00067 arrToVar(length_name, (inbuffer + offset)); 00068 offset += 4; 00069 for(unsigned int k= offset; k< offset+length_name; ++k){ 00070 inbuffer[k-1]=inbuffer[k]; 00071 } 00072 inbuffer[offset+length_name-1]=0; 00073 this->name = (char *)(inbuffer + offset-1); 00074 offset += length_name; 00075 this->offset = ((uint32_t) (*(inbuffer + offset))); 00076 this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00077 this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00078 this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00079 offset += sizeof(this->offset); 00080 this->datatype = ((uint8_t) (*(inbuffer + offset))); 00081 offset += sizeof(this->datatype); 00082 this->count = ((uint32_t) (*(inbuffer + offset))); 00083 this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00084 this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00085 this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00086 offset += sizeof(this->count); 00087 return offset; 00088 } 00089 00090 const char * getType(){ return "sensor_msgs/PointField"; }; 00091 const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; }; 00092 00093 }; 00094 00095 } 00096 #endif
Generated on Wed Jul 13 2022 23:30:18 by
