It has only one change from original one. I added robotfeedback message on it.

Dependencies:   BufferedSerial

Dependents:   RobotFeedback mobileRobotITU

Fork of ros_lib_indigo by Gary Servin

Committer:
randalthor
Date:
Sat Mar 04 14:07:56 2017 +0000
Revision:
4:80d9bee5079a
Parent:
0:fd24f7ca9688
fatih

Who changed what in which revision?

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