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_Int64MultiArray_h
jjzak 6:3c54bc7badd4 2 #define _ROS_std_msgs_Int64MultiArray_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 "std_msgs/MultiArrayLayout.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 Int64MultiArray : public ros::Msg
jjzak 6:3c54bc7badd4 14 {
jjzak 6:3c54bc7badd4 15 public:
jjzak 6:3c54bc7badd4 16 std_msgs::MultiArrayLayout layout;
jjzak 6:3c54bc7badd4 17 uint8_t data_length;
jjzak 6:3c54bc7badd4 18 int64_t st_data;
jjzak 6:3c54bc7badd4 19 int64_t * data;
jjzak 6:3c54bc7badd4 20
jjzak 6:3c54bc7badd4 21 virtual int serialize(unsigned char *outbuffer) const
jjzak 6:3c54bc7badd4 22 {
jjzak 6:3c54bc7badd4 23 int offset = 0;
jjzak 6:3c54bc7badd4 24 offset += this->layout.serialize(outbuffer + offset);
jjzak 6:3c54bc7badd4 25 *(outbuffer + offset++) = data_length;
jjzak 6:3c54bc7badd4 26 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 27 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 28 *(outbuffer + offset++) = 0;
jjzak 6:3c54bc7badd4 29 for( uint8_t i = 0; i < data_length; i++){
jjzak 6:3c54bc7badd4 30 union {
jjzak 6:3c54bc7badd4 31 int64_t real;
jjzak 6:3c54bc7badd4 32 uint64_t base;
jjzak 6:3c54bc7badd4 33 } u_datai;
jjzak 6:3c54bc7badd4 34 u_datai.real = this->data[i];
jjzak 6:3c54bc7badd4 35 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
jjzak 6:3c54bc7badd4 36 *(outbuffer + offset + 1) = (u_datai.base >> (8 * 1)) & 0xFF;
jjzak 6:3c54bc7badd4 37 *(outbuffer + offset + 2) = (u_datai.base >> (8 * 2)) & 0xFF;
jjzak 6:3c54bc7badd4 38 *(outbuffer + offset + 3) = (u_datai.base >> (8 * 3)) & 0xFF;
jjzak 6:3c54bc7badd4 39 *(outbuffer + offset + 4) = (u_datai.base >> (8 * 4)) & 0xFF;
jjzak 6:3c54bc7badd4 40 *(outbuffer + offset + 5) = (u_datai.base >> (8 * 5)) & 0xFF;
jjzak 6:3c54bc7badd4 41 *(outbuffer + offset + 6) = (u_datai.base >> (8 * 6)) & 0xFF;
jjzak 6:3c54bc7badd4 42 *(outbuffer + offset + 7) = (u_datai.base >> (8 * 7)) & 0xFF;
jjzak 6:3c54bc7badd4 43 offset += sizeof(this->data[i]);
jjzak 6:3c54bc7badd4 44 }
jjzak 6:3c54bc7badd4 45 return offset;
jjzak 6:3c54bc7badd4 46 }
jjzak 6:3c54bc7badd4 47
jjzak 6:3c54bc7badd4 48 virtual int deserialize(unsigned char *inbuffer)
jjzak 6:3c54bc7badd4 49 {
jjzak 6:3c54bc7badd4 50 int offset = 0;
jjzak 6:3c54bc7badd4 51 offset += this->layout.deserialize(inbuffer + offset);
jjzak 6:3c54bc7badd4 52 uint8_t data_lengthT = *(inbuffer + offset++);
jjzak 6:3c54bc7badd4 53 if(data_lengthT > data_length)
jjzak 6:3c54bc7badd4 54 this->data = (int64_t*)realloc(this->data, data_lengthT * sizeof(int64_t));
jjzak 6:3c54bc7badd4 55 offset += 3;
jjzak 6:3c54bc7badd4 56 data_length = data_lengthT;
jjzak 6:3c54bc7badd4 57 for( uint8_t i = 0; i < data_length; i++){
jjzak 6:3c54bc7badd4 58 union {
jjzak 6:3c54bc7badd4 59 int64_t real;
jjzak 6:3c54bc7badd4 60 uint64_t base;
jjzak 6:3c54bc7badd4 61 } u_st_data;
jjzak 6:3c54bc7badd4 62 u_st_data.base = 0;
jjzak 6:3c54bc7badd4 63 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
jjzak 6:3c54bc7badd4 64 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
jjzak 6:3c54bc7badd4 65 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
jjzak 6:3c54bc7badd4 66 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
jjzak 6:3c54bc7badd4 67 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
jjzak 6:3c54bc7badd4 68 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
jjzak 6:3c54bc7badd4 69 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
jjzak 6:3c54bc7badd4 70 u_st_data.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
jjzak 6:3c54bc7badd4 71 this->st_data = u_st_data.real;
jjzak 6:3c54bc7badd4 72 offset += sizeof(this->st_data);
jjzak 6:3c54bc7badd4 73 memcpy( &(this->data[i]), &(this->st_data), sizeof(int64_t));
jjzak 6:3c54bc7badd4 74 }
jjzak 6:3c54bc7badd4 75 return offset;
jjzak 6:3c54bc7badd4 76 }
jjzak 6:3c54bc7badd4 77
jjzak 6:3c54bc7badd4 78 const char * getType(){ return "std_msgs/Int64MultiArray"; };
jjzak 6:3c54bc7badd4 79 const char * getMD5(){ return "54865aa6c65be0448113a2afc6a49270"; };
jjzak 6:3c54bc7badd4 80
jjzak 6:3c54bc7badd4 81 };
jjzak 6:3c54bc7badd4 82
jjzak 6:3c54bc7badd4 83 }
jjzak 6:3c54bc7badd4 84 #endif