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:
garyservin
Date:
Thu Mar 31 14:22:59 2016 +0000
Revision:
0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_sensor_msgs_PointField_h
garyservin 0:fd24f7ca9688 2 #define _ROS_sensor_msgs_PointField_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
garyservin 0:fd24f7ca9688 9 namespace sensor_msgs
garyservin 0:fd24f7ca9688 10 {
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 class PointField : public ros::Msg
garyservin 0:fd24f7ca9688 13 {
garyservin 0:fd24f7ca9688 14 public:
garyservin 0:fd24f7ca9688 15 const char* name;
garyservin 0:fd24f7ca9688 16 uint32_t offset;
garyservin 0:fd24f7ca9688 17 uint8_t datatype;
garyservin 0:fd24f7ca9688 18 uint32_t count;
garyservin 0:fd24f7ca9688 19 enum { INT8 = 1 };
garyservin 0:fd24f7ca9688 20 enum { UINT8 = 2 };
garyservin 0:fd24f7ca9688 21 enum { INT16 = 3 };
garyservin 0:fd24f7ca9688 22 enum { UINT16 = 4 };
garyservin 0:fd24f7ca9688 23 enum { INT32 = 5 };
garyservin 0:fd24f7ca9688 24 enum { UINT32 = 6 };
garyservin 0:fd24f7ca9688 25 enum { FLOAT32 = 7 };
garyservin 0:fd24f7ca9688 26 enum { FLOAT64 = 8 };
garyservin 0:fd24f7ca9688 27
garyservin 0:fd24f7ca9688 28 PointField():
garyservin 0:fd24f7ca9688 29 name(""),
garyservin 0:fd24f7ca9688 30 offset(0),
garyservin 0:fd24f7ca9688 31 datatype(0),
garyservin 0:fd24f7ca9688 32 count(0)
garyservin 0:fd24f7ca9688 33 {
garyservin 0:fd24f7ca9688 34 }
garyservin 0:fd24f7ca9688 35
garyservin 0:fd24f7ca9688 36 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 37 {
garyservin 0:fd24f7ca9688 38 int offset = 0;
garyservin 0:fd24f7ca9688 39 uint32_t length_name = strlen(this->name);
garyservin 0:fd24f7ca9688 40 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
garyservin 0:fd24f7ca9688 41 offset += 4;
garyservin 0:fd24f7ca9688 42 memcpy(outbuffer + offset, this->name, length_name);
garyservin 0:fd24f7ca9688 43 offset += length_name;
garyservin 0:fd24f7ca9688 44 *(outbuffer + offset + 0) = (this->offset >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 45 *(outbuffer + offset + 1) = (this->offset >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 46 *(outbuffer + offset + 2) = (this->offset >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 47 *(outbuffer + offset + 3) = (this->offset >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 48 offset += sizeof(this->offset);
garyservin 0:fd24f7ca9688 49 *(outbuffer + offset + 0) = (this->datatype >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 50 offset += sizeof(this->datatype);
garyservin 0:fd24f7ca9688 51 *(outbuffer + offset + 0) = (this->count >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 52 *(outbuffer + offset + 1) = (this->count >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 53 *(outbuffer + offset + 2) = (this->count >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 54 *(outbuffer + offset + 3) = (this->count >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 55 offset += sizeof(this->count);
garyservin 0:fd24f7ca9688 56 return offset;
garyservin 0:fd24f7ca9688 57 }
garyservin 0:fd24f7ca9688 58
garyservin 0:fd24f7ca9688 59 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 60 {
garyservin 0:fd24f7ca9688 61 int offset = 0;
garyservin 0:fd24f7ca9688 62 uint32_t length_name;
garyservin 0:fd24f7ca9688 63 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
garyservin 0:fd24f7ca9688 64 offset += 4;
garyservin 0:fd24f7ca9688 65 for(unsigned int k= offset; k< offset+length_name; ++k){
garyservin 0:fd24f7ca9688 66 inbuffer[k-1]=inbuffer[k];
garyservin 0:fd24f7ca9688 67 }
garyservin 0:fd24f7ca9688 68 inbuffer[offset+length_name-1]=0;
garyservin 0:fd24f7ca9688 69 this->name = (char *)(inbuffer + offset-1);
garyservin 0:fd24f7ca9688 70 offset += length_name;
garyservin 0:fd24f7ca9688 71 this->offset = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 72 this->offset |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 73 this->offset |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 74 this->offset |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 75 offset += sizeof(this->offset);
garyservin 0:fd24f7ca9688 76 this->datatype = ((uint8_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 77 offset += sizeof(this->datatype);
garyservin 0:fd24f7ca9688 78 this->count = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 79 this->count |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 80 this->count |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 81 this->count |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 82 offset += sizeof(this->count);
garyservin 0:fd24f7ca9688 83 return offset;
garyservin 0:fd24f7ca9688 84 }
garyservin 0:fd24f7ca9688 85
garyservin 0:fd24f7ca9688 86 const char * getType(){ return "sensor_msgs/PointField"; };
garyservin 0:fd24f7ca9688 87 const char * getMD5(){ return "268eacb2962780ceac86cbd17e328150"; };
garyservin 0:fd24f7ca9688 88
garyservin 0:fd24f7ca9688 89 };
garyservin 0:fd24f7ca9688 90
garyservin 0:fd24f7ca9688 91 }
garyservin 0:fd24f7ca9688 92 #endif