00001 #include <math.h>
00002 #include <stdio.h>
00003 #include <stdlib.h>
00004 #include <AR/param.h>
00005 #include <AR/matrix.h>
00006 #include "calib_camera.h"
00007
00008 static double get_fitting_error( CALIB_PATT_T *patt, double dist_factor[4] );
00009 static double check_error( double *x, double *y, int num, double dist_factor[4] );
00010 static double calc_distortion2( CALIB_PATT_T *patt, double dist_factor[4] );
00011 static double get_size_factor( double dist_factor[4], int xsize, int ysize );
00012
00013 void calc_distortion( CALIB_PATT_T *patt, int xsize, int ysize, double dist_factor[4] )
00014 {
00015 int i, j;
00016 double bx, by;
00017 double bf[4];
00018 double error, min;
00019 double factor[4];
00020
00021 bx = xsize / 2;
00022 by = ysize / 2;
00023 factor[0] = bx;
00024 factor[1] = by;
00025 factor[3] = 1.0;
00026 min = calc_distortion2( patt, factor );
00027 bf[0] = factor[0];
00028 bf[1] = factor[1];
00029 bf[2] = factor[2];
00030 bf[3] = 1.0;
00031 printf("[%5.1f, %5.1f, %5.1f] %f\n", bf[0], bf[1], bf[2], min);
00032 for( j = -10; j <= 10; j++ ) {
00033 factor[1] = by + j*5;
00034 for( i = -10; i <= 10; i++ ) {
00035 factor[0] = bx + i*5;
00036 error = calc_distortion2( patt, factor );
00037 if( error < min ) { bf[0] = factor[0]; bf[1] = factor[1];
00038 bf[2] = factor[2]; min = error; }
00039 }
00040 printf("[%5.1f, %5.1f, %5.1f] %f\n", bf[0], bf[1], bf[2], min);
00041 }
00042
00043 bx = bf[0];
00044 by = bf[1];
00045 for( j = -10; j <= 10; j++ ) {
00046 factor[1] = by + 0.5 * j;
00047 for( i = -10; i <= 10; i++ ) {
00048 factor[0] = bx + 0.5 * i;
00049 error = calc_distortion2( patt, factor );
00050 if( error < min ) { bf[0] = factor[0]; bf[1] = factor[1];
00051 bf[2] = factor[2]; min = error; }
00052 }
00053 printf("[%5.1f, %5.1f, %5.1f] %f\n", bf[0], bf[1], bf[2], min);
00054 }
00055
00056 dist_factor[0] = bf[0];
00057 dist_factor[1] = bf[1];
00058 dist_factor[2] = bf[2];
00059 dist_factor[3] = get_size_factor( bf, xsize, ysize );
00060 }
00061
00062 static double get_size_factor( double dist_factor[4], int xsize, int ysize )
00063 {
00064 double ox, oy, ix, iy;
00065 double olen, ilen;
00066 double sf, sf1;
00067
00068 sf = 100.0;
00069
00070 ox = 0.0;
00071 oy = dist_factor[1];
00072 olen = dist_factor[0];
00073 arParamObserv2Ideal( dist_factor, ox, oy, &ix, &iy );
00074 ilen = dist_factor[0] - ix;
00075 printf("Olen = %f, Ilen = %f\n", olen, ilen);
00076 if( ilen > 0 ) {
00077 sf1 = ilen / olen;
00078 if( sf1 < sf ) sf = sf1;
00079 }
00080
00081 ox = xsize;
00082 oy = dist_factor[1];
00083 olen = xsize - dist_factor[0];
00084 arParamObserv2Ideal( dist_factor, ox, oy, &ix, &iy );
00085 ilen = ix - dist_factor[0];
00086 printf("Olen = %f, Ilen = %f\n", olen, ilen);
00087 if( ilen > 0 ) {
00088 sf1 = ilen / olen;
00089 if( sf1 < sf ) sf = sf1;
00090 }
00091
00092 ox = dist_factor[0];
00093 oy = 0.0;
00094 olen = dist_factor[1];
00095 arParamObserv2Ideal( dist_factor, ox, oy, &ix, &iy );
00096 ilen = dist_factor[1] - iy;
00097 printf("Olen = %f, Ilen = %f\n", olen, ilen);
00098 if( ilen > 0 ) {
00099 sf1 = ilen / olen;
00100 if( sf1 < sf ) sf = sf1;
00101 }
00102
00103 ox = dist_factor[0];
00104 oy = ysize;
00105 olen = ysize - dist_factor[1];
00106 arParamObserv2Ideal( dist_factor, ox, oy, &ix, &iy );
00107 ilen = iy - dist_factor[1];
00108 printf("Olen = %f, Ilen = %f\n", olen, ilen);
00109 if( ilen > 0 ) {
00110 sf1 = ilen / olen;
00111 if( sf1 < sf ) sf = sf1;
00112 }
00113
00114 if( sf == 0.0 ) sf = 1.0;
00115
00116 return sf;
00117 }
00118
00119 static double calc_distortion2( CALIB_PATT_T *patt, double dist_factor[4] )
00120 {
00121 double min, err, f, fb;
00122 int i;
00123
00124 dist_factor[2] = 0.0;
00125 min = get_fitting_error( patt, dist_factor );
00126
00127 f = dist_factor[2];
00128 for( i = -100; i < 200; i+=10 ) {
00129 dist_factor[2] = i;
00130 err = get_fitting_error( patt, dist_factor );
00131 if( err < min ) { min = err; f = dist_factor[2]; }
00132 }
00133
00134 fb = f;
00135 for( i = -10; i <= 10; i++ ) {
00136 dist_factor[2] = fb + i;
00137
00138
00139
00140 err = get_fitting_error( patt, dist_factor );
00141 if( err < min ) { min = err; f = dist_factor[2]; }
00142 }
00143
00144 fb = f;
00145 for( i = -10; i <= 10; i++ ) {
00146 dist_factor[2] = fb + 0.1 * i;
00147
00148
00149
00150 err = get_fitting_error( patt, dist_factor );
00151 if( err < min ) { min = err; f = dist_factor[2]; }
00152 }
00153
00154 dist_factor[2] = f;
00155 return min;
00156 }
00157
00158 static double get_fitting_error( CALIB_PATT_T *patt, double dist_factor[4] )
00159 {
00160 double *x, *y;
00161 double error;
00162 int max;
00163 int i, j, k, l;
00164 int p, c;
00165
00166 max = (patt->v_num > patt->h_num)? patt->v_num: patt->h_num;
00167 x = (double *)malloc( sizeof(double)*max );
00168 y = (double *)malloc( sizeof(double)*max );
00169 if( x == NULL || y == NULL ) exit(0);
00170
00171 error = 0.0;
00172 c = 0;
00173 for( i = 0; i < patt->loop_num; i++ ) {
00174 for( j = 0; j < patt->v_num; j++ ) {
00175 for( k = 0; k < patt->h_num; k++ ) {
00176 x[k] = patt->point[i][j*patt->h_num+k].x_coord;
00177 y[k] = patt->point[i][j*patt->h_num+k].y_coord;
00178 }
00179 error += check_error( x, y, patt->h_num, dist_factor );
00180 c += patt->h_num;
00181 }
00182
00183 for( j = 0; j < patt->h_num; j++ ) {
00184 for( k = 0; k < patt->v_num; k++ ) {
00185 x[k] = patt->point[i][k*patt->h_num+j].x_coord;
00186 y[k] = patt->point[i][k*patt->h_num+j].y_coord;
00187 }
00188 error += check_error( x, y, patt->v_num, dist_factor );
00189 c += patt->v_num;
00190 }
00191
00192 for( j = 3 - patt->v_num; j < patt->h_num - 2; j++ ) {
00193 p = 0;
00194 for( k = 0; k < patt->v_num; k++ ) {
00195 l = j+k;
00196 if( l < 0 || l >= patt->h_num ) continue;
00197 x[p] = patt->point[i][k*patt->h_num+l].x_coord;
00198 y[p] = patt->point[i][k*patt->h_num+l].y_coord;
00199 p++;
00200 }
00201 error += check_error( x, y, p, dist_factor );
00202 c += p;
00203 }
00204
00205 for( j = 2; j < patt->h_num + patt->v_num - 3; j++ ) {
00206 p = 0;
00207 for( k = 0; k < patt->v_num; k++ ) {
00208 l = j-k;
00209 if( l < 0 || l >= patt->h_num ) continue;
00210 x[p] = patt->point[i][k*patt->h_num+l].x_coord;
00211 y[p] = patt->point[i][k*patt->h_num+l].y_coord;
00212 p++;
00213 }
00214 error += check_error( x, y, p, dist_factor );
00215 c += p;
00216 }
00217 }
00218
00219 free( x );
00220 free( y );
00221
00222 return sqrt(error/c);
00223 }
00224
00225 static double check_error( double *x, double *y, int num, double dist_factor[4] )
00226 {
00227 ARMat *input, *evec;
00228 ARVec *ev, *mean;
00229 double a, b, c;
00230 double error;
00231 int i;
00232
00233 ev = arVecAlloc( 2 );
00234 mean = arVecAlloc( 2 );
00235 evec = arMatrixAlloc( 2, 2 );
00236
00237 input = arMatrixAlloc( num, 2 );
00238 for( i = 0; i < num; i++ ) {
00239 arParamObserv2Ideal( dist_factor, x[i], y[i],
00240 &(input->m[i*2+0]), &(input->m[i*2+1]) );
00241 }
00242 if( arMatrixPCA(input, evec, ev, mean) < 0 ) exit(0);
00243 a = evec->m[1];
00244 b = -evec->m[0];
00245 c = -(a*mean->v[0] + b*mean->v[1]);
00246
00247 error = 0.0;
00248 for( i = 0; i < num; i++ ) {
00249 error += (a*input->m[i*2+0] + b*input->m[i*2+1] + c)
00250 * (a*input->m[i*2+0] + b*input->m[i*2+1] + c);
00251 }
00252 error /= (a*a + b*b);
00253
00254 arMatrixFree( input );
00255 arMatrixFree( evec );
00256 arVecFree( mean );
00257 arVecFree( ev );
00258
00259 return error;
00260 }