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.
Fork of rosserial_mbed_lib by
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 char * name; 00016 uint32_t offset; 00017 uint8_t datatype; 00018 uint32_t count; 00019 enum { INT8 = 1 }; 00020 enum { UINT8 = 2 }; 00021 enum { INT16 = 3 }; 00022 enum { UINT16 = 4 }; 00023 enum { INT32 = 5 }; 00024 enum { UINT32 = 6 }; 00025 enum { FLOAT32 = 7 }; 00026 enum { FLOAT64 = 8 }; 00027 00028 virtual int serialize(unsigned char *outbuffer) const 00029 { 00030 int offset = 0; 00031 uint32_t * length_name = (uint32_t *)(outbuffer + offset); 00032 *length_name = strlen( (const char*) this->name); 00033 offset += 4; 00034 memcpy(outbuffer + offset, this->name, *length_name); 00035 offset += *length_name; 00036 *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF; 00037 *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF; 00038 *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF; 00039 *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF; 00040 offset += sizeof(this->offset); 00041 *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF; 00042 offset += sizeof(this->datatype); 00043 *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF; 00044 *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF; 00045 *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF; 00046 *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF; 00047 offset += sizeof(this->count); 00048 return offset; 00049 } 00050 00051 virtual int deserialize(unsigned char *inbuffer) 00052 { 00053 int offset = 0; 00054 uint32_t length_name = *(uint32_t *)(inbuffer + offset); 00055 offset += 4; 00056 for(unsigned int k= offset; k< offset+length_name; ++k){ 00057 inbuffer[k-1]=inbuffer[k]; 00058 } 00059 inbuffer[offset+length_name-1]=0; 00060 this->name = (char *)(inbuffer + offset-1); 00061 offset += length_name; 00062 this->offset |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00063 this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00064 this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00065 this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00066 offset += sizeof(this->offset); 00067 this->datatype |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00068 offset += sizeof(this->datatype); 00069 this->count |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00070 this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00071 this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00072 this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00073 offset += sizeof(this->count); 00074 return offset; 00075 } 00076 00077 virtual const char * getType(){ return "sensor_msgs/PointField"; }; 00078 virtual const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; }; 00079 00080 }; 00081 00082 } 00083 #endif
Generated on Tue Jul 12 2022 19:53:57 by
1.7.2
