modify for Hydro version
Fork of rosserial_mbed_lib by
std_msgs/Float64MultiArray.h@6:3c54bc7badd4, 2013-10-26 (annotated)
- Committer:
- jjzak
- Date:
- Sat Oct 26 15:39:01 2013 +0000
- Revision:
- 6:3c54bc7badd4
modify for Hydro version;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
jjzak | 6:3c54bc7badd4 | 1 | #ifndef _ROS_std_msgs_Float64MultiArray_h |
jjzak | 6:3c54bc7badd4 | 2 | #define _ROS_std_msgs_Float64MultiArray_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 Float64MultiArray : 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 | float st_data; |
jjzak | 6:3c54bc7badd4 | 19 | float * 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 | int32_t * val_datai = (int32_t *) &(this->data[i]); |
jjzak | 6:3c54bc7badd4 | 31 | int32_t exp_datai = (((*val_datai)>>23)&255); |
jjzak | 6:3c54bc7badd4 | 32 | if(exp_datai != 0) |
jjzak | 6:3c54bc7badd4 | 33 | exp_datai += 1023-127; |
jjzak | 6:3c54bc7badd4 | 34 | int32_t sig_datai = *val_datai; |
jjzak | 6:3c54bc7badd4 | 35 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 36 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 37 | *(outbuffer + offset++) = 0; |
jjzak | 6:3c54bc7badd4 | 38 | *(outbuffer + offset++) = (sig_datai<<5) & 0xff; |
jjzak | 6:3c54bc7badd4 | 39 | *(outbuffer + offset++) = (sig_datai>>3) & 0xff; |
jjzak | 6:3c54bc7badd4 | 40 | *(outbuffer + offset++) = (sig_datai>>11) & 0xff; |
jjzak | 6:3c54bc7badd4 | 41 | *(outbuffer + offset++) = ((exp_datai<<4) & 0xF0) | ((sig_datai>>19)&0x0F); |
jjzak | 6:3c54bc7badd4 | 42 | *(outbuffer + offset++) = (exp_datai>>4) & 0x7F; |
jjzak | 6:3c54bc7badd4 | 43 | if(this->data[i] < 0) *(outbuffer + offset -1) |= 0x80; |
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 = (float*)realloc(this->data, data_lengthT * sizeof(float)); |
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 | uint32_t * val_st_data = (uint32_t*) &(this->st_data); |
jjzak | 6:3c54bc7badd4 | 59 | offset += 3; |
jjzak | 6:3c54bc7badd4 | 60 | *val_st_data = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); |
jjzak | 6:3c54bc7badd4 | 61 | *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; |
jjzak | 6:3c54bc7badd4 | 62 | *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; |
jjzak | 6:3c54bc7badd4 | 63 | *val_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; |
jjzak | 6:3c54bc7badd4 | 64 | uint32_t exp_st_data = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; |
jjzak | 6:3c54bc7badd4 | 65 | exp_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; |
jjzak | 6:3c54bc7badd4 | 66 | if(exp_st_data !=0) |
jjzak | 6:3c54bc7badd4 | 67 | *val_st_data |= ((exp_st_data)-1023+127)<<23; |
jjzak | 6:3c54bc7badd4 | 68 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_data = -this->st_data; |
jjzak | 6:3c54bc7badd4 | 69 | memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); |
jjzak | 6:3c54bc7badd4 | 70 | } |
jjzak | 6:3c54bc7badd4 | 71 | return offset; |
jjzak | 6:3c54bc7badd4 | 72 | } |
jjzak | 6:3c54bc7badd4 | 73 | |
jjzak | 6:3c54bc7badd4 | 74 | const char * getType(){ return "std_msgs/Float64MultiArray"; }; |
jjzak | 6:3c54bc7badd4 | 75 | const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; }; |
jjzak | 6:3c54bc7badd4 | 76 | |
jjzak | 6:3c54bc7badd4 | 77 | }; |
jjzak | 6:3c54bc7badd4 | 78 | |
jjzak | 6:3c54bc7badd4 | 79 | } |
jjzak | 6:3c54bc7badd4 | 80 | #endif |