ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.
map_msgs/PointCloud2Update.h@2:65cba0dcf634, 2022-01-27 (annotated)
- Committer:
- gosari
- Date:
- Thu Jan 27 11:36:16 2022 +0000
- Revision:
- 2:65cba0dcf634
- Parent:
- 0:9e9b7db60fd5
for message communication with mbed
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_map_msgs_PointCloud2Update_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_map_msgs_PointCloud2Update_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 | #include "std_msgs/Header.h" |
garyservin | 0:9e9b7db60fd5 | 9 | #include "sensor_msgs/PointCloud2.h" |
garyservin | 0:9e9b7db60fd5 | 10 | |
garyservin | 0:9e9b7db60fd5 | 11 | namespace map_msgs |
garyservin | 0:9e9b7db60fd5 | 12 | { |
garyservin | 0:9e9b7db60fd5 | 13 | |
garyservin | 0:9e9b7db60fd5 | 14 | class PointCloud2Update : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 15 | { |
garyservin | 0:9e9b7db60fd5 | 16 | public: |
garyservin | 0:9e9b7db60fd5 | 17 | typedef std_msgs::Header _header_type; |
garyservin | 0:9e9b7db60fd5 | 18 | _header_type header; |
garyservin | 0:9e9b7db60fd5 | 19 | typedef uint32_t _type_type; |
garyservin | 0:9e9b7db60fd5 | 20 | _type_type type; |
garyservin | 0:9e9b7db60fd5 | 21 | typedef sensor_msgs::PointCloud2 _points_type; |
garyservin | 0:9e9b7db60fd5 | 22 | _points_type points; |
garyservin | 0:9e9b7db60fd5 | 23 | enum { ADD = 0 }; |
garyservin | 0:9e9b7db60fd5 | 24 | enum { DELETE = 1 }; |
garyservin | 0:9e9b7db60fd5 | 25 | |
garyservin | 0:9e9b7db60fd5 | 26 | PointCloud2Update(): |
garyservin | 0:9e9b7db60fd5 | 27 | header(), |
garyservin | 0:9e9b7db60fd5 | 28 | type(0), |
garyservin | 0:9e9b7db60fd5 | 29 | points() |
garyservin | 0:9e9b7db60fd5 | 30 | { |
garyservin | 0:9e9b7db60fd5 | 31 | } |
garyservin | 0:9e9b7db60fd5 | 32 | |
garyservin | 0:9e9b7db60fd5 | 33 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 34 | { |
garyservin | 0:9e9b7db60fd5 | 35 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 36 | offset += this->header.serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 37 | *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 38 | *(outbuffer + offset + 1) = (this->type >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 39 | *(outbuffer + offset + 2) = (this->type >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 40 | *(outbuffer + offset + 3) = (this->type >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 41 | offset += sizeof(this->type); |
garyservin | 0:9e9b7db60fd5 | 42 | offset += this->points.serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 43 | return offset; |
garyservin | 0:9e9b7db60fd5 | 44 | } |
garyservin | 0:9e9b7db60fd5 | 45 | |
garyservin | 0:9e9b7db60fd5 | 46 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 47 | { |
garyservin | 0:9e9b7db60fd5 | 48 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 49 | offset += this->header.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 50 | this->type = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 51 | this->type |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 52 | this->type |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 53 | this->type |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 54 | offset += sizeof(this->type); |
garyservin | 0:9e9b7db60fd5 | 55 | offset += this->points.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 56 | return offset; |
garyservin | 0:9e9b7db60fd5 | 57 | } |
garyservin | 0:9e9b7db60fd5 | 58 | |
garyservin | 0:9e9b7db60fd5 | 59 | const char * getType(){ return "map_msgs/PointCloud2Update"; }; |
garyservin | 0:9e9b7db60fd5 | 60 | const char * getMD5(){ return "6c58e4f249ae9cd2b24fb1ee0f99195e"; }; |
garyservin | 0:9e9b7db60fd5 | 61 | |
garyservin | 0:9e9b7db60fd5 | 62 | }; |
garyservin | 0:9e9b7db60fd5 | 63 | |
garyservin | 0:9e9b7db60fd5 | 64 | } |
garyservin | 0:9e9b7db60fd5 | 65 | #endif |