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_std_msgs_Header_h
jjzak 6:3c54bc7badd4 2 #define _ROS_std_msgs_Header_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 #include "ros/time.h"
jjzak 6:3c54bc7badd4 9
jjzak 6:3c54bc7badd4 10 namespace std_msgs
jjzak 6:3c54bc7badd4 11 {
jjzak 6:3c54bc7badd4 12
jjzak 6:3c54bc7badd4 13 class Header : public ros::Msg
jjzak 6:3c54bc7badd4 14 {
jjzak 6:3c54bc7badd4 15 public:
jjzak 6:3c54bc7badd4 16 uint32_t seq;
jjzak 6:3c54bc7badd4 17 ros::Time stamp;
jjzak 6:3c54bc7badd4 18 char * frame_id;
jjzak 6:3c54bc7badd4 19
jjzak 6:3c54bc7badd4 20 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 21 {
jjzak 6:3c54bc7badd4 22 int offset = 0;
jjzak 6:3c54bc7badd4 23 *(outbuffer + offset + 0) = (this->seq >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 24 *(outbuffer + offset + 1) = (this->seq >> (8 * 1)) & 0xFF;
jjzak 6:3c54bc7badd4 25 *(outbuffer + offset + 2) = (this->seq >> (8 * 2)) & 0xFF;
jjzak 6:3c54bc7badd4 26 *(outbuffer + offset + 3) = (this->seq >> (8 * 3)) & 0xFF;
jjzak 6:3c54bc7badd4 27 offset += sizeof(this->seq);
jjzak 6:3c54bc7badd4 28 *(outbuffer + offset + 0) = (this->stamp.sec >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 29 *(outbuffer + offset + 1) = (this->stamp.sec >> (8 * 1)) & 0xFF;
jjzak 6:3c54bc7badd4 30 *(outbuffer + offset + 2) = (this->stamp.sec >> (8 * 2)) & 0xFF;
jjzak 6:3c54bc7badd4 31 *(outbuffer + offset + 3) = (this->stamp.sec >> (8 * 3)) & 0xFF;
jjzak 6:3c54bc7badd4 32 offset += sizeof(this->stamp.sec);
jjzak 6:3c54bc7badd4 33 *(outbuffer + offset + 0) = (this->stamp.nsec >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 34 *(outbuffer + offset + 1) = (this->stamp.nsec >> (8 * 1)) & 0xFF;
jjzak 6:3c54bc7badd4 35 *(outbuffer + offset + 2) = (this->stamp.nsec >> (8 * 2)) & 0xFF;
jjzak 6:3c54bc7badd4 36 *(outbuffer + offset + 3) = (this->stamp.nsec >> (8 * 3)) & 0xFF;
jjzak 6:3c54bc7badd4 37 offset += sizeof(this->stamp.nsec);
jjzak 6:3c54bc7badd4 38 uint32_t length_frame_id = strlen( (const char*) this->frame_id);
jjzak 6:3c54bc7badd4 39 memcpy(outbuffer + offset, &length_frame_id, sizeof(uint32_t));
jjzak 6:3c54bc7badd4 40 offset += 4;
jjzak 6:3c54bc7badd4 41 memcpy(outbuffer + offset, this->frame_id, length_frame_id);
jjzak 6:3c54bc7badd4 42 offset += length_frame_id;
jjzak 6:3c54bc7badd4 43 return offset;
jjzak 6:3c54bc7badd4 44 }
jjzak 6:3c54bc7badd4 45
jjzak 6:3c54bc7badd4 46 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 47 {
jjzak 6:3c54bc7badd4 48 int offset = 0;
jjzak 6:3c54bc7badd4 49 this->seq = ((uint32_t) (*(inbuffer + offset)));
jjzak 6:3c54bc7badd4 50 this->seq |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
jjzak 6:3c54bc7badd4 51 this->seq |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
jjzak 6:3c54bc7badd4 52 this->seq |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
jjzak 6:3c54bc7badd4 53 offset += sizeof(this->seq);
jjzak 6:3c54bc7badd4 54 this->stamp.sec = ((uint32_t) (*(inbuffer + offset)));
jjzak 6:3c54bc7badd4 55 this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
jjzak 6:3c54bc7badd4 56 this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
jjzak 6:3c54bc7badd4 57 this->stamp.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
jjzak 6:3c54bc7badd4 58 offset += sizeof(this->stamp.sec);
jjzak 6:3c54bc7badd4 59 this->stamp.nsec = ((uint32_t) (*(inbuffer + offset)));
jjzak 6:3c54bc7badd4 60 this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
jjzak 6:3c54bc7badd4 61 this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
jjzak 6:3c54bc7badd4 62 this->stamp.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
jjzak 6:3c54bc7badd4 63 offset += sizeof(this->stamp.nsec);
jjzak 6:3c54bc7badd4 64 uint32_t length_frame_id;
jjzak 6:3c54bc7badd4 65 memcpy(&length_frame_id, (inbuffer + offset), sizeof(uint32_t));
jjzak 6:3c54bc7badd4 66 offset += 4;
jjzak 6:3c54bc7badd4 67 for(unsigned int k= offset; k< offset+length_frame_id; ++k){
jjzak 6:3c54bc7badd4 68 inbuffer[k-1]=inbuffer[k];
jjzak 6:3c54bc7badd4 69 }
jjzak 6:3c54bc7badd4 70 inbuffer[offset+length_frame_id-1]=0;
jjzak 6:3c54bc7badd4 71 this->frame_id = (char *)(inbuffer + offset-1);
jjzak 6:3c54bc7badd4 72 offset += length_frame_id;
jjzak 6:3c54bc7badd4 73 return offset;
jjzak 6:3c54bc7badd4 74 }
jjzak 6:3c54bc7badd4 75
jjzak 6:3c54bc7badd4 76 const char * getType(){ return "std_msgs/Header"; };
jjzak 6:3c54bc7badd4 77 const char * getMD5(){ return "2176decaecbce78abc3b96ef049fabed"; };
jjzak 6:3c54bc7badd4 78
jjzak 6:3c54bc7badd4 79 };
jjzak 6:3c54bc7badd4 80
jjzak 6:3c54bc7badd4 81 }
jjzak 6:3c54bc7badd4 82 #endif