00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00033 #include <stdio.h>
00034 #include <stdlib.h>
00035 #include <math.h>
00036 #include <string.h>
00037 
00038 #include "small_linalg.h"
00039 #include "rotations.h"
00040 
00041 #include "camtrans.h"
00042 
00043 #define CAMERA_EPSILON 1e-10
00044 
00045 
00046 typedef void (*warp_func_t)(const double, const double, const void*,
00047                             double*, double*);
00048 
00049 
00050 
00051 typedef struct {
00052   double w;   
00053   double h;   
00054   double cx;  
00055   double cy;
00056   double a;   
00057 
00058   
00059   double inv_w;
00060   double x_trans;
00061   double y_trans;
00062 } SphericalDistortion;
00063 
00064 
00065 
00066 static SphericalDistortion*
00067 spherical_distortion_create (const double w, const double h,
00068                              const double cx, const double cy,
00069                              const double a)
00070 {
00071   SphericalDistortion* dist =
00072     (SphericalDistortion*)malloc(sizeof(SphericalDistortion));
00073   dist->w = w;
00074   dist->h = h;
00075   dist->cx = cx;
00076   dist->cy = cy;
00077   dist->a = a*a*a*a;
00078   dist->inv_w = 1/w;
00079   dist->x_trans = 0.5 + cx;
00080   dist->y_trans = 0.5*h/w + cy;  
00081   return dist;
00082 }
00083 
00084 
00085 static void
00086 spherical_distortion_destroy(SphericalDistortion* dist)
00087 {
00088   free(dist);
00089 }
00090 
00091 
00092 
00093 static void
00094 spherical_undistort_func(const double x, const double y, const void* data,
00095                          double* ox, double* oy)
00096 {
00097   SphericalDistortion* dist = (SphericalDistortion*)data;
00098 
00099   *ox = x * dist->inv_w - dist->x_trans;
00100   *oy = y * dist->inv_w - dist->y_trans;
00101 
00102   double r2 = *ox * *ox + *oy * *oy;
00103   double new_r2 = r2/(1 - r2*dist->a);
00104 
00105   double ratio;
00106   if (fabs(r2) < 1e-8)
00107     ratio = 0;
00108   else
00109     ratio = new_r2/r2;
00110 
00111   if (ratio >= 0) {
00112     ratio = sqrt(ratio);
00113     *ox = (*ox*ratio + dist->x_trans)*dist->w;
00114     *oy = (*oy*ratio + dist->y_trans)*dist->w;
00115   }
00116   else {
00117     *ox = *oy = -1e50;
00118   }
00119 }
00120 
00121 
00122 
00123 static void
00124 spherical_distort_func(const double x, const double y, const void* data,
00125                        double* ox, double* oy)
00126 {
00127   SphericalDistortion* dist = (SphericalDistortion*)data;
00128 
00129   *ox = x * dist->inv_w - dist->x_trans;
00130   *oy = y * dist->inv_w - dist->y_trans;
00131 
00132   double r2 = *ox * *ox + *oy * *oy;
00133   double new_r2 = r2/(1 + r2*dist->a);
00134 
00135   double ratio;
00136   if (fabs(r2) < 1e-8)
00137     ratio = 0;
00138   else
00139     ratio = new_r2/r2;
00140 
00141   ratio = sqrt(ratio);
00142   *ox = (*ox*ratio + dist->x_trans)*dist->w;
00143   *oy = (*oy*ratio + dist->y_trans)*dist->w;
00144 }
00145 
00146 
00147 
00148 
00149 
00150 struct _CamTrans {
00151   double width;             
00152   double height;            
00153 
00154   double position[3];       
00155   double orientation[4];    
00156                             
00157   double fx;                
00158   double fy;                
00159   double cx;                
00160   double cy;                
00161   double skew;              
00162 
00163   double matx[12];          
00164   double inv_matx[9];       
00165 
00166   warp_func_t undist_func;  
00167   warp_func_t dist_func;    
00168   void* dist_data;          
00169 };
00170 
00171 CamTrans * 
00172 camtrans_new_spherical (double width, double height, 
00173         double fx, double fy, 
00174         double cx, double cy, double skew,
00175         const double position[3], const double orientation_quat[4],
00176         const double distortion_cx, const double distortion_cy,
00177         double distortion_param)
00178 {
00179     CamTrans *self = (CamTrans*)malloc (sizeof (CamTrans));
00180     self->width = width;
00181     self->height = height;
00182     self->fx = fx;
00183     self->fy = fy;
00184     self->cx = cx;
00185     self->cy = cy;
00186     self->skew = skew;
00187     self->position[0] = position[0];
00188     self->position[1] = position[1];
00189     self->position[2] = position[2];
00190     self->orientation[0] = orientation_quat[0];
00191     self->orientation[1] = orientation_quat[1];
00192     self->orientation[2] = orientation_quat[2];
00193     self->orientation[3] = orientation_quat[3];
00194 
00195     SphericalDistortion* dist_data;
00196     dist_data = spherical_distortion_create(self->width, self->height,
00197                                           distortion_cx, distortion_cy,
00198                                           distortion_param);
00199 
00200     
00201     self->dist_data = (void*)dist_data;
00202     self->undist_func = spherical_undistort_func;
00203     self->dist_func = spherical_distort_func;
00204 
00205     
00206     camtrans_compute_matrices (self);
00207     return self;
00208 }
00209 
00210 
00211 void camtrans_destroy (CamTrans* t)
00212 {
00213     if (NULL != t) {
00214         spherical_distortion_destroy((SphericalDistortion*)t->dist_data);
00215         free(t);
00216     }
00217 }
00218 
00219 
00220 void 
00221 camtrans_compute_matrices (CamTrans *t) 
00222 {
00223     double rot[9];
00224     double rot_trans[9];
00225     rot_quat_to_matrix(t->orientation, rot);
00226     matrix_transpose_3x3d (rot, rot_trans);
00227 
00228     double tmp_34[] = {
00229         1, 0, 0, -t->position[0],
00230         0, 1, 0, -t->position[1],
00231         0, 0, 1, -t->position[2],
00232     };
00233     double pinhole[] = {
00234         t->fx, t->skew, t->cx,
00235         0,     t->fy,   t->cy,
00236         0,     0,       1 
00237     };
00238 
00239     double tmp_33[9];
00240     matrix_multiply_3x3_3x3 (pinhole, rot_trans, tmp_33);
00241     matrix_multiply (tmp_33, 3, 3, tmp_34, 3, 4, t->matx);
00242     double m[9] = {
00243         t->matx[0], t->matx[1], t->matx[2], 
00244         t->matx[4], t->matx[5], t->matx[6], 
00245         t->matx[8], t->matx[9], t->matx[10]
00246     };
00247     int status = matrix_inverse_3x3d (m, t->inv_matx);
00248     if (0 != status) {
00249         
00250                 
00251     }
00252 }
00253 
00254 
00255 void camtrans_get_position (const CamTrans* t,
00256                                     double pos[3]) {
00257   pos[0] = t->position[0];
00258   pos[1] = t->position[1];
00259   pos[2] = t->position[2];
00260 }
00261 
00262 void camtrans_get_orientation (const CamTrans *t,
00263                                        double orientation[4]) 
00264 {
00265     orientation[0] = t->orientation[0];
00266     orientation[1] = t->orientation[1];
00267     orientation[2] = t->orientation[2];
00268     orientation[3] = t->orientation[3];
00269 }
00270 
00271 void camtrans_get_world_to_cam_matrix (const CamTrans *t, double matrix[12])
00272 {
00273     int i;
00274     for (i = 0; i < 12; ++i)
00275         matrix[i] = t->matx[i];
00276 }
00277 
00278 void camtrans_get_cam_to_world_matrix (const CamTrans *t, double matrix[9])
00279 {
00280     int i;
00281     for (i = 0; i < 9; ++i)
00282         matrix[i] = t->inv_matx[i];
00283 }
00284 
00285 double 
00286 camtrans_get_focal_length_x (const CamTrans *t)
00287 {
00288     return t->fx;
00289 }
00290 double 
00291 camtrans_get_focal_length_y (const CamTrans *t)
00292 {
00293     return t->fy;
00294 }
00295 double 
00296 camtrans_get_image_width (const CamTrans *t)
00297 {
00298     return t->width;
00299 }
00300 double 
00301 camtrans_get_image_height (const CamTrans *t)
00302 {
00303     return t->height;
00304 }
00305 double 
00306 camtrans_get_principal_x (const CamTrans *t)
00307 {
00308     return t->cx;
00309 }
00310 double 
00311 camtrans_get_principal_y (const CamTrans *t)
00312 {
00313     return t->cy;
00314 }
00315 
00316 double
00317 camtrans_get_width (const CamTrans *t)
00318 {
00319     return t->width;
00320 }
00321 
00322 double
00323 camtrans_get_height (const CamTrans *t)
00324 {
00325     return t->height;
00326 }
00327 
00328 void
00329 camtrans_get_distortion_center (const CamTrans *t,
00330                                 double *x,
00331                                 double *y)
00332 {
00333     SphericalDistortion* dist_data = (SphericalDistortion*)t->dist_data;
00334     *x = dist_data->cx;
00335     *y = dist_data->cy;
00336 }
00337 
00338 
00339 
00340 void
00341 camtrans_scale_image (CamTrans *t,
00342                               const double scale_factor)
00343 {
00344     
00345     t->width *= scale_factor;
00346     t->height *= scale_factor;
00347 
00348     
00349     t->cx *= scale_factor;
00350     t->cy *= scale_factor;
00351     t->fx *= scale_factor;
00352     t->fy *= scale_factor;
00353     t->skew *= scale_factor;
00354 
00355     
00356     int i;
00357     for (i = 0; i < 8; ++i)
00358       t->matx[i] *= scale_factor;
00359 
00360     
00361     double inv_scale_factor = 1/scale_factor;
00362     for (i = 0; i < 3; ++i) {
00363       t->inv_matx[3*i+0] *= inv_scale_factor;
00364       t->inv_matx[3*i+1] *= inv_scale_factor;
00365     }
00366 
00367     
00368     SphericalDistortion* dist_data = (SphericalDistortion*)t->dist_data;
00369     dist_data->w *= scale_factor;
00370     dist_data->h *= scale_factor;
00371     dist_data->inv_w *= inv_scale_factor;
00372 }
00373 
00374 void
00375 camtrans_rotate_camera (CamTrans *t,
00376                         const double q[4]) {
00377     
00378     double tmp_q[4];
00379     rot_quat_mult (tmp_q, t->orientation, q);
00380     t->orientation[0] = tmp_q[0];
00381     t->orientation[1] = tmp_q[1];
00382     t->orientation[2] = tmp_q[2];
00383     t->orientation[3] = tmp_q[3];
00384 
00385     
00386     camtrans_compute_matrices (t);
00387 }
00388 
00389 void
00390 camtrans_set_distortion_center (CamTrans *t,
00391                                 const double cx, const double cy)
00392 {
00393     SphericalDistortion* dist_data = (SphericalDistortion*)t->dist_data;
00394     dist_data->cx = cx;
00395     dist_data->cy = cy;
00396     dist_data->x_trans = 0.5 + cx;
00397     dist_data->y_trans = 0.5*t->height/t->width + cy;  
00398 }
00399 
00400 
00401 
00402 
00403 
00404 int 
00405 camtrans_undistort_pixel (const CamTrans* cam,
00406                                   const double x, const double y,
00407                                   double* ox, double* oy)
00408 {
00409     cam->undist_func(x,y,cam->dist_data,ox,oy);
00410     return 0;
00411 }
00412 
00413 
00414 
00415 int 
00416 camtrans_distort_pixel (const CamTrans* cam,
00417                                 const double x, const double y,
00418                                 double* ox, double* oy)
00419 {
00420     cam->dist_func(x,y,cam->dist_data,ox,oy);
00421     return 0;
00422 }
00423 
00424 int camtrans_pixel_to_ray (const CamTrans* cam,
00425                                   const double x, const double y,
00426                                   double ray[3]) {
00427     double u, v;
00428     int ret;
00429 
00430     ret = camtrans_undistort_pixel(cam, x, y, &u, &v);
00431     if (ret < 0)
00432         return ret;
00433 
00434     const double* inv = cam->inv_matx;
00435 
00436     ray[0] = u*inv[0] + v*inv[1] + inv[2];
00437     ray[1] = u*inv[3] + v*inv[4] + inv[5];
00438     ray[2] = u*inv[6] + v*inv[7] + inv[8];
00439 
00440     return 0;
00441 }
00442 
00443 int 
00444 camtrans_project_point (const CamTrans* cam,
00445                                 const double * p_world,
00446                                 const int distort,
00447                                 double* ox, double* oy, double *oz)
00448 {
00449     double tx, ty, tz;
00450 
00451     double x = p_world[0];
00452     double y = p_world[1];
00453     double z = p_world[2];
00454 
00455     const double* m = cam->matx;
00456     tx = m[0]*x + m[1]*y + m[2]*z + m[3];
00457     ty = m[4]*x + m[5]*y + m[6]*z + m[7];
00458     tz = m[8]*x + m[9]*y + m[10]*z + m[11];
00459 
00460     if (fabs (tz) < CAMERA_EPSILON) return -1;
00461 
00462     double inv_z = 1/tz;
00463     tx *= inv_z;
00464     ty *= inv_z;
00465     if (oz) *oz = tz;
00466 
00467     if (distort != 0)
00468         return camtrans_distort_pixel(cam,tx,ty,ox,oy);
00469     else {
00470         if (ox) *ox = tx;
00471         if (oy) *oy = ty;
00472         return 0;
00473     }
00474 }
00475 
00476 
00477 
00478 int camtrans_project_line (const CamTrans *cam,
00479                            const double *l_world,
00480                            double *ox, double *oy, double *oz)
00481 {
00482     double tx, ty, tz;
00483 
00484     double x = l_world[0];
00485     double y = l_world[1];
00486     double z = l_world[2];
00487 
00488     
00489     const double* m = cam->inv_matx;
00490     tx = m[0]*x + m[3]*y + m[6]*z;
00491     ty = m[1]*x + m[4]*y + m[7]*z;
00492     tz = m[2]*x + m[5]*y + m[8]*z;
00493 
00494     double inv_mag = sqrt(tx*tx + ty*ty);
00495     if (inv_mag < CAMERA_EPSILON)
00496       return -1;
00497 
00498     inv_mag = 1/inv_mag;
00499     *ox = tx*inv_mag;
00500     *oy = ty*inv_mag;
00501     *oz = tz*inv_mag;
00502     return 0;
00503 }