00001 #ifndef _ROS_std_msgs_Float64MultiArray_h 00002 #define _ROS_std_msgs_Float64MultiArray_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "std_msgs/MultiArrayLayout.h" 00009 00010 namespace std_msgs 00011 { 00012 00013 class Float64MultiArray : public ros::Msg 00014 { 00015 public: 00016 std_msgs::MultiArrayLayout layout; 00017 uint8_t data_length; 00018 float st_data; 00019 float * data; 00020 00021 virtual int serialize(unsigned char *outbuffer) const 00022 { 00023 int offset = 0; 00024 offset += this->layout.serialize(outbuffer + offset); 00025 *(outbuffer + offset++) = data_length; 00026 *(outbuffer + offset++) = 0; 00027 *(outbuffer + offset++) = 0; 00028 *(outbuffer + offset++) = 0; 00029 for( uint8_t i = 0; i < data_length; i++){ 00030 int32_t * val_datai = (long *) &(this->data[i]); 00031 int32_t exp_datai = (((*val_datai)>>23)&255); 00032 if(exp_datai != 0) 00033 exp_datai += 1023-127; 00034 int32_t sig_datai = *val_datai; 00035 *(outbuffer + offset++) = 0; 00036 *(outbuffer + offset++) = 0; 00037 *(outbuffer + offset++) = 0; 00038 *(outbuffer + offset++) = (sig_datai<<5) & 0xff; 00039 *(outbuffer + offset++) = (sig_datai>>3) & 0xff; 00040 *(outbuffer + offset++) = (sig_datai>>11) & 0xff; 00041 *(outbuffer + offset++) = ((exp_datai<<4) & 0xF0) | ((sig_datai>>19)&0x0F); 00042 *(outbuffer + offset++) = (exp_datai>>4) & 0x7F; 00043 if(this->data[i] < 0) *(outbuffer + offset -1) |= 0x80; 00044 } 00045 return offset; 00046 } 00047 00048 virtual int deserialize(unsigned char *inbuffer) 00049 { 00050 int offset = 0; 00051 offset += this->layout.deserialize(inbuffer + offset); 00052 uint8_t data_lengthT = *(inbuffer + offset++); 00053 if(data_lengthT > data_length) 00054 this->data = (float*)realloc(this->data, data_lengthT * sizeof(float)); 00055 offset += 3; 00056 data_length = data_lengthT; 00057 for( uint8_t i = 0; i < data_length; i++){ 00058 uint32_t * val_st_data = (uint32_t*) &(this->st_data); 00059 offset += 3; 00060 *val_st_data = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); 00061 *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; 00062 *val_st_data |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; 00063 *val_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; 00064 uint32_t exp_st_data = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; 00065 exp_st_data |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; 00066 if(exp_st_data !=0) 00067 *val_st_data |= ((exp_st_data)-1023+127)<<23; 00068 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_data = -this->st_data; 00069 memcpy( &(this->data[i]), &(this->st_data), sizeof(float)); 00070 } 00071 return offset; 00072 } 00073 00074 const char * getType(){ return "std_msgs/Float64MultiArray"; }; 00075 const char * getMD5(){ return "4b7d974086d4060e7db4613a7e6c3ba4"; }; 00076 00077 }; 00078 00079 } 00080 #endif