modify for Hydro version

Dependencies:   MODSERIAL

Fork of rosserial_mbed_lib by nucho

Committer:
jjzak
Date:
Sat Oct 26 15:39:01 2013 +0000
Revision:
6:3c54bc7badd4
modify for Hydro version;

Who changed what in which revision?

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