Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
jvfausto
Date:
Fri Nov 02 21:48:22 2018 +0000
Revision:
2:ab8333331642
Parent:
0:9e9b7db60fd5
Working towards twists

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_sensor_msgs_PointCloud_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_sensor_msgs_PointCloud_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 "geometry_msgs/Point32.h"
garyservin 0:9e9b7db60fd5 10 #include "sensor_msgs/ChannelFloat32.h"
garyservin 0:9e9b7db60fd5 11
garyservin 0:9e9b7db60fd5 12 namespace sensor_msgs
garyservin 0:9e9b7db60fd5 13 {
garyservin 0:9e9b7db60fd5 14
garyservin 0:9e9b7db60fd5 15 class PointCloud : public ros::Msg
garyservin 0:9e9b7db60fd5 16 {
garyservin 0:9e9b7db60fd5 17 public:
garyservin 0:9e9b7db60fd5 18 typedef std_msgs::Header _header_type;
garyservin 0:9e9b7db60fd5 19 _header_type header;
garyservin 0:9e9b7db60fd5 20 uint32_t points_length;
garyservin 0:9e9b7db60fd5 21 typedef geometry_msgs::Point32 _points_type;
garyservin 0:9e9b7db60fd5 22 _points_type st_points;
garyservin 0:9e9b7db60fd5 23 _points_type * points;
garyservin 0:9e9b7db60fd5 24 uint32_t channels_length;
garyservin 0:9e9b7db60fd5 25 typedef sensor_msgs::ChannelFloat32 _channels_type;
garyservin 0:9e9b7db60fd5 26 _channels_type st_channels;
garyservin 0:9e9b7db60fd5 27 _channels_type * channels;
garyservin 0:9e9b7db60fd5 28
garyservin 0:9e9b7db60fd5 29 PointCloud():
garyservin 0:9e9b7db60fd5 30 header(),
garyservin 0:9e9b7db60fd5 31 points_length(0), points(NULL),
garyservin 0:9e9b7db60fd5 32 channels_length(0), channels(NULL)
garyservin 0:9e9b7db60fd5 33 {
garyservin 0:9e9b7db60fd5 34 }
garyservin 0:9e9b7db60fd5 35
garyservin 0:9e9b7db60fd5 36 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 37 {
garyservin 0:9e9b7db60fd5 38 int offset = 0;
garyservin 0:9e9b7db60fd5 39 offset += this->header.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 40 *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 41 *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 42 *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 43 *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 44 offset += sizeof(this->points_length);
garyservin 0:9e9b7db60fd5 45 for( uint32_t i = 0; i < points_length; i++){
garyservin 0:9e9b7db60fd5 46 offset += this->points[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 47 }
garyservin 0:9e9b7db60fd5 48 *(outbuffer + offset + 0) = (this->channels_length >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 49 *(outbuffer + offset + 1) = (this->channels_length >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 50 *(outbuffer + offset + 2) = (this->channels_length >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 51 *(outbuffer + offset + 3) = (this->channels_length >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 52 offset += sizeof(this->channels_length);
garyservin 0:9e9b7db60fd5 53 for( uint32_t i = 0; i < channels_length; i++){
garyservin 0:9e9b7db60fd5 54 offset += this->channels[i].serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 55 }
garyservin 0:9e9b7db60fd5 56 return offset;
garyservin 0:9e9b7db60fd5 57 }
garyservin 0:9e9b7db60fd5 58
garyservin 0:9e9b7db60fd5 59 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 60 {
garyservin 0:9e9b7db60fd5 61 int offset = 0;
garyservin 0:9e9b7db60fd5 62 offset += this->header.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 63 uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 64 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 65 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 66 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 67 offset += sizeof(this->points_length);
garyservin 0:9e9b7db60fd5 68 if(points_lengthT > points_length)
garyservin 0:9e9b7db60fd5 69 this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
garyservin 0:9e9b7db60fd5 70 points_length = points_lengthT;
garyservin 0:9e9b7db60fd5 71 for( uint32_t i = 0; i < points_length; i++){
garyservin 0:9e9b7db60fd5 72 offset += this->st_points.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 73 memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
garyservin 0:9e9b7db60fd5 74 }
garyservin 0:9e9b7db60fd5 75 uint32_t channels_lengthT = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:9e9b7db60fd5 76 channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 77 channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 78 channels_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 79 offset += sizeof(this->channels_length);
garyservin 0:9e9b7db60fd5 80 if(channels_lengthT > channels_length)
garyservin 0:9e9b7db60fd5 81 this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32));
garyservin 0:9e9b7db60fd5 82 channels_length = channels_lengthT;
garyservin 0:9e9b7db60fd5 83 for( uint32_t i = 0; i < channels_length; i++){
garyservin 0:9e9b7db60fd5 84 offset += this->st_channels.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 85 memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32));
garyservin 0:9e9b7db60fd5 86 }
garyservin 0:9e9b7db60fd5 87 return offset;
garyservin 0:9e9b7db60fd5 88 }
garyservin 0:9e9b7db60fd5 89
garyservin 0:9e9b7db60fd5 90 const char * getType(){ return "sensor_msgs/PointCloud"; };
garyservin 0:9e9b7db60fd5 91 const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; };
garyservin 0:9e9b7db60fd5 92
garyservin 0:9e9b7db60fd5 93 };
garyservin 0:9e9b7db60fd5 94
garyservin 0:9e9b7db60fd5 95 }
garyservin 0:9e9b7db60fd5 96 #endif