Go to the documentation of this file.00001 #ifndef _ROS_sensor_msgs_CameraInfo_h
00002 #define _ROS_sensor_msgs_CameraInfo_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "sensor_msgs/RegionOfInterest.h"
00010
00011 namespace sensor_msgs
00012 {
00013
00014 class CameraInfo : public ros::Msg
00015 {
00016 public:
00017 std_msgs::Header header;
00018 uint32_t height;
00019 uint32_t width;
00020 const char* distortion_model;
00021 uint8_t D_length;
00022 float st_D;
00023 float * D;
00024 float K[9];
00025 float R[9];
00026 float P[12];
00027 uint32_t binning_x;
00028 uint32_t binning_y;
00029 sensor_msgs::RegionOfInterest roi;
00030
00031 virtual int serialize(unsigned char *outbuffer) const
00032 {
00033 int offset = 0;
00034 offset += this->header.serialize(outbuffer + offset);
00035 *(outbuffer + offset + 0) = (this->height >> (8 * 0)) & 0xFF;
00036 *(outbuffer + offset + 1) = (this->height >> (8 * 1)) & 0xFF;
00037 *(outbuffer + offset + 2) = (this->height >> (8 * 2)) & 0xFF;
00038 *(outbuffer + offset + 3) = (this->height >> (8 * 3)) & 0xFF;
00039 offset += sizeof(this->height);
00040 *(outbuffer + offset + 0) = (this->width >> (8 * 0)) & 0xFF;
00041 *(outbuffer + offset + 1) = (this->width >> (8 * 1)) & 0xFF;
00042 *(outbuffer + offset + 2) = (this->width >> (8 * 2)) & 0xFF;
00043 *(outbuffer + offset + 3) = (this->width >> (8 * 3)) & 0xFF;
00044 offset += sizeof(this->width);
00045 uint32_t length_distortion_model = strlen(this->distortion_model);
00046 memcpy(outbuffer + offset, &length_distortion_model, sizeof(uint32_t));
00047 offset += 4;
00048 memcpy(outbuffer + offset, this->distortion_model, length_distortion_model);
00049 offset += length_distortion_model;
00050 *(outbuffer + offset++) = D_length;
00051 *(outbuffer + offset++) = 0;
00052 *(outbuffer + offset++) = 0;
00053 *(outbuffer + offset++) = 0;
00054 for( uint8_t i = 0; i < D_length; i++){
00055 int32_t * val_Di = (int32_t *) &(this->D[i]);
00056 int32_t exp_Di = (((*val_Di)>>23)&255);
00057 if(exp_Di != 0)
00058 exp_Di += 1023-127;
00059 int32_t sig_Di = *val_Di;
00060 *(outbuffer + offset++) = 0;
00061 *(outbuffer + offset++) = 0;
00062 *(outbuffer + offset++) = 0;
00063 *(outbuffer + offset++) = (sig_Di<<5) & 0xff;
00064 *(outbuffer + offset++) = (sig_Di>>3) & 0xff;
00065 *(outbuffer + offset++) = (sig_Di>>11) & 0xff;
00066 *(outbuffer + offset++) = ((exp_Di<<4) & 0xF0) | ((sig_Di>>19)&0x0F);
00067 *(outbuffer + offset++) = (exp_Di>>4) & 0x7F;
00068 if(this->D[i] < 0) *(outbuffer + offset -1) |= 0x80;
00069 }
00070 for( uint8_t i = 0; i < 9; i++){
00071 int32_t * val_Ki = (int32_t *) &(this->K[i]);
00072 int32_t exp_Ki = (((*val_Ki)>>23)&255);
00073 if(exp_Ki != 0)
00074 exp_Ki += 1023-127;
00075 int32_t sig_Ki = *val_Ki;
00076 *(outbuffer + offset++) = 0;
00077 *(outbuffer + offset++) = 0;
00078 *(outbuffer + offset++) = 0;
00079 *(outbuffer + offset++) = (sig_Ki<<5) & 0xff;
00080 *(outbuffer + offset++) = (sig_Ki>>3) & 0xff;
00081 *(outbuffer + offset++) = (sig_Ki>>11) & 0xff;
00082 *(outbuffer + offset++) = ((exp_Ki<<4) & 0xF0) | ((sig_Ki>>19)&0x0F);
00083 *(outbuffer + offset++) = (exp_Ki>>4) & 0x7F;
00084 if(this->K[i] < 0) *(outbuffer + offset -1) |= 0x80;
00085 }
00086 for( uint8_t i = 0; i < 9; i++){
00087 int32_t * val_Ri = (int32_t *) &(this->R[i]);
00088 int32_t exp_Ri = (((*val_Ri)>>23)&255);
00089 if(exp_Ri != 0)
00090 exp_Ri += 1023-127;
00091 int32_t sig_Ri = *val_Ri;
00092 *(outbuffer + offset++) = 0;
00093 *(outbuffer + offset++) = 0;
00094 *(outbuffer + offset++) = 0;
00095 *(outbuffer + offset++) = (sig_Ri<<5) & 0xff;
00096 *(outbuffer + offset++) = (sig_Ri>>3) & 0xff;
00097 *(outbuffer + offset++) = (sig_Ri>>11) & 0xff;
00098 *(outbuffer + offset++) = ((exp_Ri<<4) & 0xF0) | ((sig_Ri>>19)&0x0F);
00099 *(outbuffer + offset++) = (exp_Ri>>4) & 0x7F;
00100 if(this->R[i] < 0) *(outbuffer + offset -1) |= 0x80;
00101 }
00102 for( uint8_t i = 0; i < 12; i++){
00103 int32_t * val_Pi = (int32_t *) &(this->P[i]);
00104 int32_t exp_Pi = (((*val_Pi)>>23)&255);
00105 if(exp_Pi != 0)
00106 exp_Pi += 1023-127;
00107 int32_t sig_Pi = *val_Pi;
00108 *(outbuffer + offset++) = 0;
00109 *(outbuffer + offset++) = 0;
00110 *(outbuffer + offset++) = 0;
00111 *(outbuffer + offset++) = (sig_Pi<<5) & 0xff;
00112 *(outbuffer + offset++) = (sig_Pi>>3) & 0xff;
00113 *(outbuffer + offset++) = (sig_Pi>>11) & 0xff;
00114 *(outbuffer + offset++) = ((exp_Pi<<4) & 0xF0) | ((sig_Pi>>19)&0x0F);
00115 *(outbuffer + offset++) = (exp_Pi>>4) & 0x7F;
00116 if(this->P[i] < 0) *(outbuffer + offset -1) |= 0x80;
00117 }
00118 *(outbuffer + offset + 0) = (this->binning_x >> (8 * 0)) & 0xFF;
00119 *(outbuffer + offset + 1) = (this->binning_x >> (8 * 1)) & 0xFF;
00120 *(outbuffer + offset + 2) = (this->binning_x >> (8 * 2)) & 0xFF;
00121 *(outbuffer + offset + 3) = (this->binning_x >> (8 * 3)) & 0xFF;
00122 offset += sizeof(this->binning_x);
00123 *(outbuffer + offset + 0) = (this->binning_y >> (8 * 0)) & 0xFF;
00124 *(outbuffer + offset + 1) = (this->binning_y >> (8 * 1)) & 0xFF;
00125 *(outbuffer + offset + 2) = (this->binning_y >> (8 * 2)) & 0xFF;
00126 *(outbuffer + offset + 3) = (this->binning_y >> (8 * 3)) & 0xFF;
00127 offset += sizeof(this->binning_y);
00128 offset += this->roi.serialize(outbuffer + offset);
00129 return offset;
00130 }
00131
00132 virtual int deserialize(unsigned char *inbuffer)
00133 {
00134 int offset = 0;
00135 offset += this->header.deserialize(inbuffer + offset);
00136 this->height = ((uint32_t) (*(inbuffer + offset)));
00137 this->height |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00138 this->height |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00139 this->height |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00140 offset += sizeof(this->height);
00141 this->width = ((uint32_t) (*(inbuffer + offset)));
00142 this->width |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00143 this->width |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00144 this->width |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00145 offset += sizeof(this->width);
00146 uint32_t length_distortion_model;
00147 memcpy(&length_distortion_model, (inbuffer + offset), sizeof(uint32_t));
00148 offset += 4;
00149 for(unsigned int k= offset; k< offset+length_distortion_model; ++k){
00150 inbuffer[k-1]=inbuffer[k];
00151 }
00152 inbuffer[offset+length_distortion_model-1]=0;
00153 this->distortion_model = (char *)(inbuffer + offset-1);
00154 offset += length_distortion_model;
00155 uint8_t D_lengthT = *(inbuffer + offset++);
00156 if(D_lengthT > D_length)
00157 this->D = (float*)realloc(this->D, D_lengthT * sizeof(float));
00158 offset += 3;
00159 D_length = D_lengthT;
00160 for( uint8_t i = 0; i < D_length; i++){
00161 uint32_t * val_st_D = (uint32_t*) &(this->st_D);
00162 offset += 3;
00163 *val_st_D = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00164 *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00165 *val_st_D |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00166 *val_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00167 uint32_t exp_st_D = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00168 exp_st_D |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00169 if(exp_st_D !=0)
00170 *val_st_D |= ((exp_st_D)-1023+127)<<23;
00171 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->st_D = -this->st_D;
00172 memcpy( &(this->D[i]), &(this->st_D), sizeof(float));
00173 }
00174 for( uint8_t i = 0; i < 9; i++){
00175 uint32_t * val_Ki = (uint32_t*) &(this->K[i]);
00176 offset += 3;
00177 *val_Ki = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00178 *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00179 *val_Ki |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00180 *val_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00181 uint32_t exp_Ki = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00182 exp_Ki |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00183 if(exp_Ki !=0)
00184 *val_Ki |= ((exp_Ki)-1023+127)<<23;
00185 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->K[i] = -this->K[i];
00186 }
00187 for( uint8_t i = 0; i < 9; i++){
00188 uint32_t * val_Ri = (uint32_t*) &(this->R[i]);
00189 offset += 3;
00190 *val_Ri = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00191 *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00192 *val_Ri |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00193 *val_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00194 uint32_t exp_Ri = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00195 exp_Ri |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00196 if(exp_Ri !=0)
00197 *val_Ri |= ((exp_Ri)-1023+127)<<23;
00198 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->R[i] = -this->R[i];
00199 }
00200 for( uint8_t i = 0; i < 12; i++){
00201 uint32_t * val_Pi = (uint32_t*) &(this->P[i]);
00202 offset += 3;
00203 *val_Pi = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00204 *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00205 *val_Pi |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00206 *val_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00207 uint32_t exp_Pi = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00208 exp_Pi |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00209 if(exp_Pi !=0)
00210 *val_Pi |= ((exp_Pi)-1023+127)<<23;
00211 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->P[i] = -this->P[i];
00212 }
00213 this->binning_x = ((uint32_t) (*(inbuffer + offset)));
00214 this->binning_x |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00215 this->binning_x |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00216 this->binning_x |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00217 offset += sizeof(this->binning_x);
00218 this->binning_y = ((uint32_t) (*(inbuffer + offset)));
00219 this->binning_y |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00220 this->binning_y |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00221 this->binning_y |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00222 offset += sizeof(this->binning_y);
00223 offset += this->roi.deserialize(inbuffer + offset);
00224 return offset;
00225 }
00226
00227 const char * getType(){ return "sensor_msgs/CameraInfo"; };
00228 const char * getMD5(){ return "c9a58c1b0b154e0e6da7578cb991d214"; };
00229
00230 };
00231
00232 }
00233 #endif