modify for Hydro version
Fork of rosserial_mbed_lib by
sensor_msgs/CameraInfo.h@0:77afd7560544, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:30 2011 +0000
- Revision:
- 0:77afd7560544
- Child:
- 3:1cf99502f396
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:77afd7560544 | 1 | #ifndef ros_CameraInfo_h |
nucho | 0:77afd7560544 | 2 | #define ros_CameraInfo_h |
nucho | 0:77afd7560544 | 3 | |
nucho | 0:77afd7560544 | 4 | #include <stdint.h> |
nucho | 0:77afd7560544 | 5 | #include <string.h> |
nucho | 0:77afd7560544 | 6 | #include <stdlib.h> |
nucho | 0:77afd7560544 | 7 | #include "../ros/msg.h" |
nucho | 0:77afd7560544 | 8 | #include "std_msgs/Header.h" |
nucho | 0:77afd7560544 | 9 | #include "sensor_msgs/RegionOfInterest.h" |
nucho | 0:77afd7560544 | 10 | |
nucho | 0:77afd7560544 | 11 | namespace sensor_msgs |
nucho | 0:77afd7560544 | 12 | { |
nucho | 0:77afd7560544 | 13 | |
nucho | 0:77afd7560544 | 14 | class CameraInfo : public ros::Msg |
nucho | 0:77afd7560544 | 15 | { |
nucho | 0:77afd7560544 | 16 | public: |
nucho | 0:77afd7560544 | 17 | std_msgs::Header header; |
nucho | 0:77afd7560544 | 18 | unsigned long height; |
nucho | 0:77afd7560544 | 19 | unsigned long width; |
nucho | 0:77afd7560544 | 20 | char * distortion_model; |
nucho | 0:77afd7560544 | 21 | unsigned char D_length; |
nucho | 0:77afd7560544 | 22 | float st_D; |
nucho | 0:77afd7560544 | 23 | float * D; |
nucho | 0:77afd7560544 | 24 | float K[9]; |
nucho | 0:77afd7560544 | 25 | float R[9]; |
nucho | 0:77afd7560544 | 26 | float P[12]; |
nucho | 0:77afd7560544 | 27 | unsigned long binning_x; |
nucho | 0:77afd7560544 | 28 | unsigned long binning_y; |
nucho | 0:77afd7560544 | 29 | sensor_msgs::RegionOfInterest roi; |
nucho | 0:77afd7560544 | 30 | |
nucho | 0:77afd7560544 | 31 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:77afd7560544 | 32 | { |
nucho | 0:77afd7560544 | 33 | int offset = 0; |
nucho | 0:77afd7560544 | 34 | offset += this->header.serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 35 | union { |
nucho | 0:77afd7560544 | 36 | unsigned long real; |
nucho | 0:77afd7560544 | 37 | unsigned long base; |
nucho | 0:77afd7560544 | 38 | } u_height; |
nucho | 0:77afd7560544 | 39 | u_height.real = this->height; |
nucho | 0:77afd7560544 | 40 | *(outbuffer + offset + 0) = (u_height.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 41 | *(outbuffer + offset + 1) = (u_height.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 42 | *(outbuffer + offset + 2) = (u_height.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 43 | *(outbuffer + offset + 3) = (u_height.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 44 | offset += sizeof(this->height); |
nucho | 0:77afd7560544 | 45 | union { |
nucho | 0:77afd7560544 | 46 | unsigned long real; |
nucho | 0:77afd7560544 | 47 | unsigned long base; |
nucho | 0:77afd7560544 | 48 | } u_width; |
nucho | 0:77afd7560544 | 49 | u_width.real = this->width; |
nucho | 0:77afd7560544 | 50 | *(outbuffer + offset + 0) = (u_width.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 51 | *(outbuffer + offset + 1) = (u_width.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 52 | *(outbuffer + offset + 2) = (u_width.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 53 | *(outbuffer + offset + 3) = (u_width.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 54 | offset += sizeof(this->width); |
nucho | 0:77afd7560544 | 55 | long * length_distortion_model = (long *)(outbuffer + offset); |
nucho | 0:77afd7560544 | 56 | *length_distortion_model = strlen( (const char*) this->distortion_model); |
nucho | 0:77afd7560544 | 57 | offset += 4; |
nucho | 0:77afd7560544 | 58 | memcpy(outbuffer + offset, this->distortion_model, *length_distortion_model); |
nucho | 0:77afd7560544 | 59 | offset += *length_distortion_model; |
nucho | 0:77afd7560544 | 60 | *(outbuffer + offset++) = D_length; |
nucho | 0:77afd7560544 | 61 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 62 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 63 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 64 | for( unsigned char i = 0; i < D_length; i++){ |
nucho | 0:77afd7560544 | 65 | long * val_Di = (long *) &(this->D[i]); |
nucho | 0:77afd7560544 | 66 | long exp_Di = (((*val_Di)>>23)&255); |
nucho | 0:77afd7560544 | 67 | if(exp_Di != 0) |
nucho | 0:77afd7560544 | 68 | exp_Di += 1023-127; |
nucho | 0:77afd7560544 | 69 | long sig_Di = *val_Di; |
nucho | 0:77afd7560544 | 70 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 71 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 72 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 73 | *(outbuffer + offset++) = (sig_Di<<5) & 0xff; |
nucho | 0:77afd7560544 | 74 | *(outbuffer + offset++) = (sig_Di>>3) & 0xff; |
nucho | 0:77afd7560544 | 75 | *(outbuffer + offset++) = (sig_Di>>11) & 0xff; |
nucho | 0:77afd7560544 | 76 | *(outbuffer + offset++) = ((exp_Di<<4) & 0xF0) | ((sig_Di>>19)&0x0F); |
nucho | 0:77afd7560544 | 77 | *(outbuffer + offset++) = (exp_Di>>4) & 0x7F; |
nucho | 0:77afd7560544 | 78 | if(this->D[i] < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:77afd7560544 | 79 | } |
nucho | 0:77afd7560544 | 80 | unsigned char * K_val = (unsigned char *) this->K; |
nucho | 0:77afd7560544 | 81 | for( unsigned char i = 0; i < 9; i++){ |
nucho | 0:77afd7560544 | 82 | long * val_Ki = (long *) &(this->K[i]); |
nucho | 0:77afd7560544 | 83 | long exp_Ki = (((*val_Ki)>>23)&255); |
nucho | 0:77afd7560544 | 84 | if(exp_Ki != 0) |
nucho | 0:77afd7560544 | 85 | exp_Ki += 1023-127; |
nucho | 0:77afd7560544 | 86 | long sig_Ki = *val_Ki; |
nucho | 0:77afd7560544 | 87 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 88 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 89 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 90 | *(outbuffer + offset++) = (sig_Ki<<5) & 0xff; |
nucho | 0:77afd7560544 | 91 | *(outbuffer + offset++) = (sig_Ki>>3) & 0xff; |
nucho | 0:77afd7560544 | 92 | *(outbuffer + offset++) = (sig_Ki>>11) & 0xff; |
nucho | 0:77afd7560544 | 93 | *(outbuffer + offset++) = ((exp_Ki<<4) & 0xF0) | ((sig_Ki>>19)&0x0F); |
nucho | 0:77afd7560544 | 94 | *(outbuffer + offset++) = (exp_Ki>>4) & 0x7F; |
nucho | 0:77afd7560544 | 95 | if(this->K[i] < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:77afd7560544 | 96 | } |
nucho | 0:77afd7560544 | 97 | unsigned char * R_val = (unsigned char *) this->R; |
nucho | 0:77afd7560544 | 98 | for( unsigned char i = 0; i < 9; i++){ |
nucho | 0:77afd7560544 | 99 | long * val_Ri = (long *) &(this->R[i]); |
nucho | 0:77afd7560544 | 100 | long exp_Ri = (((*val_Ri)>>23)&255); |
nucho | 0:77afd7560544 | 101 | if(exp_Ri != 0) |
nucho | 0:77afd7560544 | 102 | exp_Ri += 1023-127; |
nucho | 0:77afd7560544 | 103 | long sig_Ri = *val_Ri; |
nucho | 0:77afd7560544 | 104 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 105 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 106 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 107 | *(outbuffer + offset++) = (sig_Ri<<5) & 0xff; |
nucho | 0:77afd7560544 | 108 | *(outbuffer + offset++) = (sig_Ri>>3) & 0xff; |
nucho | 0:77afd7560544 | 109 | *(outbuffer + offset++) = (sig_Ri>>11) & 0xff; |
nucho | 0:77afd7560544 | 110 | *(outbuffer + offset++) = ((exp_Ri<<4) & 0xF0) | ((sig_Ri>>19)&0x0F); |
nucho | 0:77afd7560544 | 111 | *(outbuffer + offset++) = (exp_Ri>>4) & 0x7F; |
nucho | 0:77afd7560544 | 112 | if(this->R[i] < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:77afd7560544 | 113 | } |
nucho | 0:77afd7560544 | 114 | unsigned char * P_val = (unsigned char *) this->P; |
nucho | 0:77afd7560544 | 115 | for( unsigned char i = 0; i < 12; i++){ |
nucho | 0:77afd7560544 | 116 | long * val_Pi = (long *) &(this->P[i]); |
nucho | 0:77afd7560544 | 117 | long exp_Pi = (((*val_Pi)>>23)&255); |
nucho | 0:77afd7560544 | 118 | if(exp_Pi != 0) |
nucho | 0:77afd7560544 | 119 | exp_Pi += 1023-127; |
nucho | 0:77afd7560544 | 120 | long sig_Pi = *val_Pi; |
nucho | 0:77afd7560544 | 121 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 122 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 123 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 124 | *(outbuffer + offset++) = (sig_Pi<<5) & 0xff; |
nucho | 0:77afd7560544 | 125 | *(outbuffer + offset++) = (sig_Pi>>3) & 0xff; |
nucho | 0:77afd7560544 | 126 | *(outbuffer + offset++) = (sig_Pi>>11) & 0xff; |
nucho | 0:77afd7560544 | 127 | *(outbuffer + offset++) = ((exp_Pi<<4) & 0xF0) | ((sig_Pi>>19)&0x0F); |
nucho | 0:77afd7560544 | 128 | *(outbuffer + offset++) = (exp_Pi>>4) & 0x7F; |
nucho | 0:77afd7560544 | 129 | if(this->P[i] < 0) *(outbuffer + offset -1) |= 0x80; |
nucho | 0:77afd7560544 | 130 | } |
nucho | 0:77afd7560544 | 131 | union { |
nucho | 0:77afd7560544 | 132 | unsigned long real; |
nucho | 0:77afd7560544 | 133 | unsigned long base; |
nucho | 0:77afd7560544 | 134 | } u_binning_x; |
nucho | 0:77afd7560544 | 135 | u_binning_x.real = this->binning_x; |
nucho | 0:77afd7560544 | 136 | *(outbuffer + offset + 0) = (u_binning_x.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 137 | *(outbuffer + offset + 1) = (u_binning_x.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 138 | *(outbuffer + offset + 2) = (u_binning_x.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 139 | *(outbuffer + offset + 3) = (u_binning_x.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 140 | offset += sizeof(this->binning_x); |
nucho | 0:77afd7560544 | 141 | union { |
nucho | 0:77afd7560544 | 142 | unsigned long real; |
nucho | 0:77afd7560544 | 143 | unsigned long base; |
nucho | 0:77afd7560544 | 144 | } u_binning_y; |
nucho | 0:77afd7560544 | 145 | u_binning_y.real = this->binning_y; |
nucho | 0:77afd7560544 | 146 | *(outbuffer + offset + 0) = (u_binning_y.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 147 | *(outbuffer + offset + 1) = (u_binning_y.base >> (8 * 1)) & 0xFF; |
nucho | 0:77afd7560544 | 148 | *(outbuffer + offset + 2) = (u_binning_y.base >> (8 * 2)) & 0xFF; |
nucho | 0:77afd7560544 | 149 | *(outbuffer + offset + 3) = (u_binning_y.base >> (8 * 3)) & 0xFF; |
nucho | 0:77afd7560544 | 150 | offset += sizeof(this->binning_y); |
nucho | 0:77afd7560544 | 151 | offset += this->roi.serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 152 | return offset; |
nucho | 0:77afd7560544 | 153 | } |
nucho | 0:77afd7560544 | 154 | |
nucho | 0:77afd7560544 | 155 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 156 | { |
nucho | 0:77afd7560544 | 157 | int offset = 0; |
nucho | 0:77afd7560544 | 158 | offset += this->header.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 159 | union { |
nucho | 0:77afd7560544 | 160 | unsigned long real; |
nucho | 0:77afd7560544 | 161 | unsigned long base; |
nucho | 0:77afd7560544 | 162 | } u_height; |
nucho | 0:77afd7560544 | 163 | u_height.base = 0; |
nucho | 0:77afd7560544 | 164 | u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 165 | u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:77afd7560544 | 166 | u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:77afd7560544 | 167 | u_height.base |= ((typeof(u_height.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 168 | this->height = u_height.real; |
nucho | 0:77afd7560544 | 169 | offset += sizeof(this->height); |
nucho | 0:77afd7560544 | 170 | union { |
nucho | 0:77afd7560544 | 171 | unsigned long real; |
nucho | 0:77afd7560544 | 172 | unsigned long base; |
nucho | 0:77afd7560544 | 173 | } u_width; |
nucho | 0:77afd7560544 | 174 | u_width.base = 0; |
nucho | 0:77afd7560544 | 175 | u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 176 | u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:77afd7560544 | 177 | u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:77afd7560544 | 178 | u_width.base |= ((typeof(u_width.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 179 | this->width = u_width.real; |
nucho | 0:77afd7560544 | 180 | offset += sizeof(this->width); |
nucho | 0:77afd7560544 | 181 | uint32_t length_distortion_model = *(uint32_t *)(inbuffer + offset); |
nucho | 0:77afd7560544 | 182 | offset += 4; |
nucho | 0:77afd7560544 | 183 | for(unsigned int k= offset; k< offset+length_distortion_model; ++k){ |
nucho | 0:77afd7560544 | 184 | inbuffer[k-1]=inbuffer[k]; |
nucho | 0:77afd7560544 | 185 | } |
nucho | 0:77afd7560544 | 186 | inbuffer[offset+length_distortion_model-1]=0; |
nucho | 0:77afd7560544 | 187 | this->distortion_model = (char *)(inbuffer + offset-1); |
nucho | 0:77afd7560544 | 188 | offset += length_distortion_model; |
nucho | 0:77afd7560544 | 189 | unsigned char D_lengthT = *(inbuffer + offset++); |
nucho | 0:77afd7560544 | 190 | if(D_lengthT > D_length) |
nucho | 0:77afd7560544 | 191 | this->D = (float*)realloc(this->D, D_lengthT * sizeof(float)); |
nucho | 0:77afd7560544 | 192 | offset += 3; |
nucho | 0:77afd7560544 | 193 | D_length = D_lengthT; |
nucho | 0:77afd7560544 | 194 | for( unsigned char i = 0; i < D_length; i++){ |
nucho | 0:77afd7560544 | 195 | unsigned long * val_st_D = (unsigned long*) &(this->st_D); |
nucho | 0:77afd7560544 | 196 | offset += 3; |
nucho | 0:77afd7560544 | 197 | *val_st_D = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 0:77afd7560544 | 198 | *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 0:77afd7560544 | 199 | *val_st_D |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 0:77afd7560544 | 200 | *val_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 0:77afd7560544 | 201 | unsigned long exp_st_D = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 0:77afd7560544 | 202 | exp_st_D |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 203 | if(exp_st_D !=0) |
nucho | 0:77afd7560544 | 204 | *val_st_D |= ((exp_st_D)-1023+127)<<23; |
nucho | 0:77afd7560544 | 205 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_D = -this->st_D; |
nucho | 0:77afd7560544 | 206 | memcpy( &(this->D[i]), &(this->st_D), sizeof(float)); |
nucho | 0:77afd7560544 | 207 | } |
nucho | 0:77afd7560544 | 208 | unsigned char * K_val = (unsigned char *) this->K; |
nucho | 0:77afd7560544 | 209 | for( unsigned char i = 0; i < 9; i++){ |
nucho | 0:77afd7560544 | 210 | unsigned long * val_Ki = (unsigned long*) &(this->K[i]); |
nucho | 0:77afd7560544 | 211 | offset += 3; |
nucho | 0:77afd7560544 | 212 | *val_Ki = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 0:77afd7560544 | 213 | *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 0:77afd7560544 | 214 | *val_Ki |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 0:77afd7560544 | 215 | *val_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 0:77afd7560544 | 216 | unsigned long exp_Ki = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 0:77afd7560544 | 217 | exp_Ki |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 218 | if(exp_Ki !=0) |
nucho | 0:77afd7560544 | 219 | *val_Ki |= ((exp_Ki)-1023+127)<<23; |
nucho | 0:77afd7560544 | 220 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->K[i] = -this->K[i]; |
nucho | 0:77afd7560544 | 221 | } |
nucho | 0:77afd7560544 | 222 | unsigned char * R_val = (unsigned char *) this->R; |
nucho | 0:77afd7560544 | 223 | for( unsigned char i = 0; i < 9; i++){ |
nucho | 0:77afd7560544 | 224 | unsigned long * val_Ri = (unsigned long*) &(this->R[i]); |
nucho | 0:77afd7560544 | 225 | offset += 3; |
nucho | 0:77afd7560544 | 226 | *val_Ri = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 0:77afd7560544 | 227 | *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 0:77afd7560544 | 228 | *val_Ri |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 0:77afd7560544 | 229 | *val_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 0:77afd7560544 | 230 | unsigned long exp_Ri = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 0:77afd7560544 | 231 | exp_Ri |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 232 | if(exp_Ri !=0) |
nucho | 0:77afd7560544 | 233 | *val_Ri |= ((exp_Ri)-1023+127)<<23; |
nucho | 0:77afd7560544 | 234 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->R[i] = -this->R[i]; |
nucho | 0:77afd7560544 | 235 | } |
nucho | 0:77afd7560544 | 236 | unsigned char * P_val = (unsigned char *) this->P; |
nucho | 0:77afd7560544 | 237 | for( unsigned char i = 0; i < 12; i++){ |
nucho | 0:77afd7560544 | 238 | unsigned long * val_Pi = (unsigned long*) &(this->P[i]); |
nucho | 0:77afd7560544 | 239 | offset += 3; |
nucho | 0:77afd7560544 | 240 | *val_Pi = ((unsigned long)(*(inbuffer + offset++))>>5 & 0x07); |
nucho | 0:77afd7560544 | 241 | *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<3; |
nucho | 0:77afd7560544 | 242 | *val_Pi |= ((unsigned long)(*(inbuffer + offset++)) & 0xff)<<11; |
nucho | 0:77afd7560544 | 243 | *val_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x0f)<<19; |
nucho | 0:77afd7560544 | 244 | unsigned long exp_Pi = ((unsigned long)(*(inbuffer + offset++))&0xf0)>>4; |
nucho | 0:77afd7560544 | 245 | exp_Pi |= ((unsigned long)(*(inbuffer + offset)) & 0x7f)<<4; |
nucho | 0:77afd7560544 | 246 | if(exp_Pi !=0) |
nucho | 0:77afd7560544 | 247 | *val_Pi |= ((exp_Pi)-1023+127)<<23; |
nucho | 0:77afd7560544 | 248 | if( ((*(inbuffer+offset++)) & 0x80) > 0) this->P[i] = -this->P[i]; |
nucho | 0:77afd7560544 | 249 | } |
nucho | 0:77afd7560544 | 250 | union { |
nucho | 0:77afd7560544 | 251 | unsigned long real; |
nucho | 0:77afd7560544 | 252 | unsigned long base; |
nucho | 0:77afd7560544 | 253 | } u_binning_x; |
nucho | 0:77afd7560544 | 254 | u_binning_x.base = 0; |
nucho | 0:77afd7560544 | 255 | u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 256 | u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:77afd7560544 | 257 | u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:77afd7560544 | 258 | u_binning_x.base |= ((typeof(u_binning_x.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 259 | this->binning_x = u_binning_x.real; |
nucho | 0:77afd7560544 | 260 | offset += sizeof(this->binning_x); |
nucho | 0:77afd7560544 | 261 | union { |
nucho | 0:77afd7560544 | 262 | unsigned long real; |
nucho | 0:77afd7560544 | 263 | unsigned long base; |
nucho | 0:77afd7560544 | 264 | } u_binning_y; |
nucho | 0:77afd7560544 | 265 | u_binning_y.base = 0; |
nucho | 0:77afd7560544 | 266 | u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 267 | u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:77afd7560544 | 268 | u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:77afd7560544 | 269 | u_binning_y.base |= ((typeof(u_binning_y.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:77afd7560544 | 270 | this->binning_y = u_binning_y.real; |
nucho | 0:77afd7560544 | 271 | offset += sizeof(this->binning_y); |
nucho | 0:77afd7560544 | 272 | offset += this->roi.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 273 | return offset; |
nucho | 0:77afd7560544 | 274 | } |
nucho | 0:77afd7560544 | 275 | |
nucho | 0:77afd7560544 | 276 | virtual const char * getType(){ return "sensor_msgs/CameraInfo"; }; |
nucho | 0:77afd7560544 | 277 | |
nucho | 0:77afd7560544 | 278 | }; |
nucho | 0:77afd7560544 | 279 | |
nucho | 0:77afd7560544 | 280 | } |
nucho | 0:77afd7560544 | 281 | #endif |