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