hairo
Dependencies: mbed BufferedSerial
sensor_msgs/PointField.h@0:9e9b7db60fd5, 2016-12-31 (annotated)
- Committer:
- garyservin
- Date:
- Sat Dec 31 00:48:34 2016 +0000
- Revision:
- 0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_sensor_msgs_PointField_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_sensor_msgs_PointField_h |
garyservin | 0:9e9b7db60fd5 | 3 | |
garyservin | 0:9e9b7db60fd5 | 4 | #include <stdint.h> |
garyservin | 0:9e9b7db60fd5 | 5 | #include <string.h> |
garyservin | 0:9e9b7db60fd5 | 6 | #include <stdlib.h> |
garyservin | 0:9e9b7db60fd5 | 7 | #include "ros/msg.h" |
garyservin | 0:9e9b7db60fd5 | 8 | |
garyservin | 0:9e9b7db60fd5 | 9 | namespace sensor_msgs |
garyservin | 0:9e9b7db60fd5 | 10 | { |
garyservin | 0:9e9b7db60fd5 | 11 | |
garyservin | 0:9e9b7db60fd5 | 12 | class PointField : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 13 | { |
garyservin | 0:9e9b7db60fd5 | 14 | public: |
garyservin | 0:9e9b7db60fd5 | 15 | typedef const char* _name_type; |
garyservin | 0:9e9b7db60fd5 | 16 | _name_type name; |
garyservin | 0:9e9b7db60fd5 | 17 | typedef uint32_t _offset_type; |
garyservin | 0:9e9b7db60fd5 | 18 | _offset_type offset; |
garyservin | 0:9e9b7db60fd5 | 19 | typedef uint8_t _datatype_type; |
garyservin | 0:9e9b7db60fd5 | 20 | _datatype_type datatype; |
garyservin | 0:9e9b7db60fd5 | 21 | typedef uint32_t _count_type; |
garyservin | 0:9e9b7db60fd5 | 22 | _count_type count; |
garyservin | 0:9e9b7db60fd5 | 23 | enum { INT8 = 1 }; |
garyservin | 0:9e9b7db60fd5 | 24 | enum { UINT8 = 2 }; |
garyservin | 0:9e9b7db60fd5 | 25 | enum { INT16 = 3 }; |
garyservin | 0:9e9b7db60fd5 | 26 | enum { UINT16 = 4 }; |
garyservin | 0:9e9b7db60fd5 | 27 | enum { INT32 = 5 }; |
garyservin | 0:9e9b7db60fd5 | 28 | enum { UINT32 = 6 }; |
garyservin | 0:9e9b7db60fd5 | 29 | enum { FLOAT32 = 7 }; |
garyservin | 0:9e9b7db60fd5 | 30 | enum { FLOAT64 = 8 }; |
garyservin | 0:9e9b7db60fd5 | 31 | |
garyservin | 0:9e9b7db60fd5 | 32 | PointField(): |
garyservin | 0:9e9b7db60fd5 | 33 | name(""), |
garyservin | 0:9e9b7db60fd5 | 34 | offset(0), |
garyservin | 0:9e9b7db60fd5 | 35 | datatype(0), |
garyservin | 0:9e9b7db60fd5 | 36 | count(0) |
garyservin | 0:9e9b7db60fd5 | 37 | { |
garyservin | 0:9e9b7db60fd5 | 38 | } |
garyservin | 0:9e9b7db60fd5 | 39 | |
garyservin | 0:9e9b7db60fd5 | 40 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 41 | { |
garyservin | 0:9e9b7db60fd5 | 42 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 43 | uint32_t length_name = strlen(this->name); |
garyservin | 0:9e9b7db60fd5 | 44 | varToArr(outbuffer + offset, length_name); |
garyservin | 0:9e9b7db60fd5 | 45 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 46 | memcpy(outbuffer + offset, this->name, length_name); |
garyservin | 0:9e9b7db60fd5 | 47 | offset += length_name; |
garyservin | 0:9e9b7db60fd5 | 48 | *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 49 | *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 50 | *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 51 | *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 52 | offset += sizeof(this->offset); |
garyservin | 0:9e9b7db60fd5 | 53 | *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 54 | offset += sizeof(this->datatype); |
garyservin | 0:9e9b7db60fd5 | 55 | *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 56 | *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 57 | *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 58 | *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 59 | offset += sizeof(this->count); |
garyservin | 0:9e9b7db60fd5 | 60 | return offset; |
garyservin | 0:9e9b7db60fd5 | 61 | } |
garyservin | 0:9e9b7db60fd5 | 62 | |
garyservin | 0:9e9b7db60fd5 | 63 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 64 | { |
garyservin | 0:9e9b7db60fd5 | 65 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 66 | uint32_t length_name; |
garyservin | 0:9e9b7db60fd5 | 67 | arrToVar(length_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 68 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 69 | for(unsigned int k= offset; k< offset+length_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 70 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 71 | } |
garyservin | 0:9e9b7db60fd5 | 72 | inbuffer[offset+length_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 73 | this->name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 74 | offset += length_name; |
garyservin | 0:9e9b7db60fd5 | 75 | this->offset = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 76 | this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 77 | this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 78 | this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 79 | offset += sizeof(this->offset); |
garyservin | 0:9e9b7db60fd5 | 80 | this->datatype = ((uint8_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 81 | offset += sizeof(this->datatype); |
garyservin | 0:9e9b7db60fd5 | 82 | this->count = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 83 | this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 84 | this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 85 | this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 86 | offset += sizeof(this->count); |
garyservin | 0:9e9b7db60fd5 | 87 | return offset; |
garyservin | 0:9e9b7db60fd5 | 88 | } |
garyservin | 0:9e9b7db60fd5 | 89 | |
garyservin | 0:9e9b7db60fd5 | 90 | const char * getType(){ return "sensor_msgs/PointField"; }; |
garyservin | 0:9e9b7db60fd5 | 91 | const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; }; |
garyservin | 0:9e9b7db60fd5 | 92 | |
garyservin | 0:9e9b7db60fd5 | 93 | }; |
garyservin | 0:9e9b7db60fd5 | 94 | |
garyservin | 0:9e9b7db60fd5 | 95 | } |
garyservin | 0:9e9b7db60fd5 | 96 | #endif |