Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h

Dependencies:   BufferedSerial

Dependents:   WRS2020_mecanum_node

Committer:
sgrsn
Date:
Mon Nov 02 09:00:01 2020 +0000
Revision:
2:5d429be7d0aa
Parent:
0:04ac6be8229a
Change INPUT_SIZE and OUTPUT_SIZE on node_handle.h to pub sub

Who changed what in which revision?

UserRevisionLine numberNew contents of line
Gary Servin 0:04ac6be8229a 1 #ifndef _ROS_map_msgs_PointCloud2Update_h
Gary Servin 0:04ac6be8229a 2 #define _ROS_map_msgs_PointCloud2Update_h
Gary Servin 0:04ac6be8229a 3
Gary Servin 0:04ac6be8229a 4 #include <stdint.h>
Gary Servin 0:04ac6be8229a 5 #include <string.h>
Gary Servin 0:04ac6be8229a 6 #include <stdlib.h>
Gary Servin 0:04ac6be8229a 7 #include "ros/msg.h"
Gary Servin 0:04ac6be8229a 8 #include "std_msgs/Header.h"
Gary Servin 0:04ac6be8229a 9 #include "sensor_msgs/PointCloud2.h"
Gary Servin 0:04ac6be8229a 10
Gary Servin 0:04ac6be8229a 11 namespace map_msgs
Gary Servin 0:04ac6be8229a 12 {
Gary Servin 0:04ac6be8229a 13
Gary Servin 0:04ac6be8229a 14 class PointCloud2Update : public ros::Msg
Gary Servin 0:04ac6be8229a 15 {
Gary Servin 0:04ac6be8229a 16 public:
Gary Servin 0:04ac6be8229a 17 typedef std_msgs::Header _header_type;
Gary Servin 0:04ac6be8229a 18 _header_type header;
Gary Servin 0:04ac6be8229a 19 typedef uint32_t _type_type;
Gary Servin 0:04ac6be8229a 20 _type_type type;
Gary Servin 0:04ac6be8229a 21 typedef sensor_msgs::PointCloud2 _points_type;
Gary Servin 0:04ac6be8229a 22 _points_type points;
Gary Servin 0:04ac6be8229a 23 enum { ADD = 0 };
Gary Servin 0:04ac6be8229a 24 enum { DELETE = 1 };
Gary Servin 0:04ac6be8229a 25
Gary Servin 0:04ac6be8229a 26 PointCloud2Update():
Gary Servin 0:04ac6be8229a 27 header(),
Gary Servin 0:04ac6be8229a 28 type(0),
Gary Servin 0:04ac6be8229a 29 points()
Gary Servin 0:04ac6be8229a 30 {
Gary Servin 0:04ac6be8229a 31 }
Gary Servin 0:04ac6be8229a 32
Gary Servin 0:04ac6be8229a 33 virtual int serialize(unsigned char *outbuffer) const
Gary Servin 0:04ac6be8229a 34 {
Gary Servin 0:04ac6be8229a 35 int offset = 0;
Gary Servin 0:04ac6be8229a 36 offset += this->header.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 37 *(outbuffer + offset + 0) = (this->type >> (8 * 0)) & 0xFF;
Gary Servin 0:04ac6be8229a 38 *(outbuffer + offset + 1) = (this->type >> (8 * 1)) & 0xFF;
Gary Servin 0:04ac6be8229a 39 *(outbuffer + offset + 2) = (this->type >> (8 * 2)) & 0xFF;
Gary Servin 0:04ac6be8229a 40 *(outbuffer + offset + 3) = (this->type >> (8 * 3)) & 0xFF;
Gary Servin 0:04ac6be8229a 41 offset += sizeof(this->type);
Gary Servin 0:04ac6be8229a 42 offset += this->points.serialize(outbuffer + offset);
Gary Servin 0:04ac6be8229a 43 return offset;
Gary Servin 0:04ac6be8229a 44 }
Gary Servin 0:04ac6be8229a 45
Gary Servin 0:04ac6be8229a 46 virtual int deserialize(unsigned char *inbuffer)
Gary Servin 0:04ac6be8229a 47 {
Gary Servin 0:04ac6be8229a 48 int offset = 0;
Gary Servin 0:04ac6be8229a 49 offset += this->header.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 50 this->type = ((uint32_t) (*(inbuffer + offset)));
Gary Servin 0:04ac6be8229a 51 this->type |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
Gary Servin 0:04ac6be8229a 52 this->type |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
Gary Servin 0:04ac6be8229a 53 this->type |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
Gary Servin 0:04ac6be8229a 54 offset += sizeof(this->type);
Gary Servin 0:04ac6be8229a 55 offset += this->points.deserialize(inbuffer + offset);
Gary Servin 0:04ac6be8229a 56 return offset;
Gary Servin 0:04ac6be8229a 57 }
Gary Servin 0:04ac6be8229a 58
Gary Servin 0:04ac6be8229a 59 const char * getType(){ return "map_msgs/PointCloud2Update"; };
Gary Servin 0:04ac6be8229a 60 const char * getMD5(){ return "6c58e4f249ae9cd2b24fb1ee0f99195e"; };
Gary Servin 0:04ac6be8229a 61
Gary Servin 0:04ac6be8229a 62 };
Gary Servin 0:04ac6be8229a 63
Gary Servin 0:04ac6be8229a 64 }
Gary Servin 0:04ac6be8229a 65 #endif