icp.c
Go to the documentation of this file.
00001 #include <math.h>
00002 #include <string.h>
00003 
00004 #include <gsl/gsl_matrix.h>
00005 
00006 #include <gpc/gpc.h>
00007 #include <egsl/egsl_macros.h>
00008 
00009 #include "../csm_all.h"
00010 
00011 #include "icp.h"
00012 
00013 
00014 void sm_journal_open(const char* file) {
00015         file = 0;
00016 /*      journal_open(file);*/
00017 }
00018 
00019 void ld_invalid_if_outside(LDP ld, double min_reading, double max_reading) {
00020         int i;
00021         for(i=0;i<ld->nrays;i++) {
00022                 if(!ld_valid_ray(ld, i)) continue;
00023                 double r = ld->readings[i];
00024                 if( r <= min_reading || r > max_reading)
00025                         ld->valid[i] = 0;
00026         }
00027 }
00028 
00029 void sm_icp(struct sm_params*params, struct sm_result*res) {
00030         res->valid = 0;
00031 
00032         LDP laser_ref  = params->laser_ref;
00033         LDP laser_sens = params->laser_sens;
00034         
00035         if(!ld_valid_fields(laser_ref) || 
00036            !ld_valid_fields(laser_sens)) {
00037                 return;
00038         }
00039         
00040         sm_debug("sm_icp: laser_sens has %d/%d; laser_ref has %d/%d rays valid\n",
00041                 count_equal(laser_sens->valid, laser_sens->nrays, 1), laser_sens->nrays,
00042                 count_equal(laser_ref->valid, laser_ref->nrays, 1), laser_ref->nrays);
00043         
00044         
00046         ld_invalid_if_outside(laser_ref, params->min_reading, params->max_reading);
00047         ld_invalid_if_outside(laser_sens, params->min_reading, params->max_reading);
00048         
00049         sm_debug("sm_icp:  laser_sens has %d/%d; laser_ref has %d/%d rays valid (after removing outside interval [%f, %f])\n",
00050                 count_equal(laser_sens->valid, laser_sens->nrays, 1), laser_sens->nrays,
00051                 count_equal(laser_ref->valid, laser_ref->nrays, 1), laser_ref->nrays,
00052            params->min_reading, params->max_reading);
00053         
00054         if(JJ) jj_context_enter("sm_icp");
00055         
00056         egsl_push_named("sm_icp");
00057         
00058                         
00059         if(params->use_corr_tricks || params->debug_verify_tricks)
00060                 ld_create_jump_tables(laser_ref);
00061                 
00062         ld_compute_cartesian(laser_ref);
00063         ld_compute_cartesian(laser_sens);
00064 
00065         if(params->do_alpha_test) {
00066                 ld_simple_clustering(laser_ref, params->clustering_threshold);
00067                 ld_compute_orientation(laser_ref, params->orientation_neighbourhood, params->sigma);
00068                 ld_simple_clustering(laser_sens, params->clustering_threshold);
00069                 ld_compute_orientation(laser_sens, params->orientation_neighbourhood, params->sigma);
00070         }
00071 
00072         if(JJ) jj_add("laser_ref",  ld_to_json(laser_ref));
00073         if(JJ) jj_add("laser_sens", ld_to_json(laser_sens));
00074         
00075         gsl_vector * x_new = gsl_vector_alloc(3);
00076         gsl_vector * x_old = vector_from_array(3, params->first_guess);
00077         
00078         if(params->do_visibility_test) {
00079                 sm_debug("laser_ref:\n");
00080                 visibilityTest(laser_ref, x_old);
00081 
00082                 sm_debug("laser_sens:\n");
00083                 gsl_vector * minus_x_old = gsl_vector_alloc(3);
00084                 ominus(x_old,minus_x_old);
00085                 visibilityTest(laser_sens, minus_x_old);
00086                 gsl_vector_free(minus_x_old);
00087         }
00088         
00089         double error;
00090         int iterations;
00091         int nvalid;
00092         if(!icp_loop(params, x_old->data, x_new->data, &error, &nvalid, &iterations)) {
00093                 sm_error("icp: ICP failed for some reason. \n");
00094                 res->valid = 0;
00095                 res->iterations = iterations;
00096                 res->nvalid = 0;
00097                 
00098         } else {
00099                 /* It was succesfull */
00100                 
00101                 double best_error = error;
00102                 gsl_vector * best_x = gsl_vector_alloc(3);
00103                 gsl_vector_memcpy(best_x, x_new);
00104 
00105                 if(params->restart && 
00106                         (error/nvalid)>(params->restart_threshold_mean_error) ) {
00107                         sm_debug("Restarting: %f > %f \n",(error/nvalid),(params->restart_threshold_mean_error));
00108                         double dt  = params->restart_dt;
00109                         double dth = params->restart_dtheta;
00110                         sm_debug("icp_loop: dt = %f dtheta= %f deg\n",dt,rad2deg(dth));
00111                 
00112                         double perturb[6][3] = {
00113                                 {dt,0,0}, {-dt,0,0},
00114                                 {0,dt,0}, {0,-dt,0},
00115                                 {0,0,dth}, {0,0,-dth}
00116                         };
00117 
00118                         int a; for(a=0;a<6;a++){
00119                                 sm_debug("-- Restarting with perturbation #%d\n", a);
00120                                 struct sm_params my_params = *params;
00121                                 gsl_vector * start = gsl_vector_alloc(3);
00122                                         gvs(start, 0, gvg(x_new,0)+perturb[a][0]);
00123                                         gvs(start, 1, gvg(x_new,1)+perturb[a][1]);
00124                                         gvs(start, 2, gvg(x_new,2)+perturb[a][2]);
00125                                 gsl_vector * x_a = gsl_vector_alloc(3);
00126                                 double my_error; int my_valid; int my_iterations;
00127                                 if(!icp_loop(&my_params, start->data, x_a->data, &my_error, &my_valid, &my_iterations)){
00128                                         sm_error("Error during restart #%d/%d. \n", a, 6);
00129                                         break;
00130                                 }
00131                                 iterations+=my_iterations;
00132                 
00133                                 if(my_error < best_error) {
00134                                         sm_debug("--Perturbation #%d resulted in error %f < %f\n", a,my_error,best_error);
00135                                         gsl_vector_memcpy(best_x, x_a);
00136                                         best_error = my_error;
00137                                 }
00138                                 gsl_vector_free(x_a); gsl_vector_free(start);
00139                         }
00140                 }
00141         
00142         
00143                 /* At last, we did it. */
00144                 res->valid = 1;
00145                 vector_to_array(best_x, res->x);
00146                 sm_debug("icp: final x =  %s  \n", gsl_friendly_pose(best_x));
00147         
00148         
00149                 if(params->do_compute_covariance)  {
00150 
00151                         val cov0_x, dx_dy1, dx_dy2;
00152                         compute_covariance_exact(
00153                                 laser_ref, laser_sens, best_x,
00154                                 &cov0_x, &dx_dy1, &dx_dy2);
00155                 
00156                         val cov_x = sc(square(params->sigma), cov0_x); 
00157 /*                      egsl_v2da(cov_x, res->cov_x); */
00158                 
00159                         res->cov_x_m = egsl_v2gslm(cov_x);
00160                         res->dx_dy1_m = egsl_v2gslm(dx_dy1);
00161                         res->dx_dy2_m = egsl_v2gslm(dx_dy2);
00162                 
00163                         if(0) {
00164                                 egsl_print("cov0_x", cov0_x);
00165                                 egsl_print_spectrum("cov0_x", cov0_x);
00166                 
00167                                 val fim = ld_fisher0(laser_ref);
00168                                 val ifim = inv(fim);
00169                                 egsl_print("fim", fim);
00170                                 egsl_print_spectrum("ifim", ifim);
00171                         }
00172                 }
00173         
00174                 res->error = best_error;
00175                 res->iterations = iterations;
00176                 res->nvalid = nvalid;
00177 
00178                 gsl_vector_free(best_x);
00179         }
00180         gsl_vector_free(x_new);
00181         gsl_vector_free(x_old);
00182 
00183 
00184         egsl_pop_named("sm_icp");
00185 
00186         if(JJ) jj_context_exit();
00187 }


csm_ros
Author(s): Gaƫl Ecorchard , Ivan Dryanovski, William Morris, Andrea Censi
autogenerated on Sat Jun 8 2019 19:52:42