icp_loop.c
Go to the documentation of this file.
1 #include <math.h>
2 #include <string.h>
3 
4 #include <gsl/gsl_matrix.h>
5 
6 #include <gpc/gpc.h>
7 #include <egsl/egsl_macros.h>
8 
9 #include "../csm_all.h"
10 
11 #include "icp.h"
12 
13 int icp_loop(struct sm_params*params, const double*q0, double*x_new,
14  double*total_error, int*valid, int*iterations) {
15  if(any_nan(q0,3)) {
16  sm_error("icp_loop: Initial pose contains nan: %s\n", friendly_pose(q0));
17  return 0;
18  }
19 
20 
21  LDP laser_sens = params->laser_sens;
22  double x_old[3], delta[3], delta_old[3] = {0,0,0};
23  copy_d(q0, 3, x_old);
24  unsigned int hashes[params->max_iterations];
25  int iteration;
26 
27  sm_debug("icp: starting at q0 = %s \n", friendly_pose(x_old));
28 
29  if(JJ) jj_loop_enter("iterations");
30 
31  int all_is_okay = 1;
32 
33  for(iteration=0; iteration<params->max_iterations;iteration++) {
34  if(JJ) jj_loop_iteration();
35  if(JJ) jj_add_double_array("x_old", x_old, 3);
36 
37  egsl_push_named("icp_loop iteration");
38  sm_debug("== icp_loop: starting iteration. %d \n", iteration);
39 
42  ld_compute_world_coords(laser_sens, x_old);
43 
45  if(params->use_corr_tricks)
47  else
48  find_correspondences(params);
49 
52  if(params->debug_verify_tricks)
53  debug_correspondences(params);
54 
55  /* If not many correspondences, bail out */
56  int num_corr = ld_num_valid_correspondences(laser_sens);
57  double fail_perc = 0.05;
58  if(num_corr < fail_perc * laser_sens->nrays) { /* TODO: arbitrary */
59  sm_error(" : before trimming, only %d correspondences.\n",num_corr);
60  all_is_okay = 0;
61  egsl_pop_named("icp_loop iteration"); /* loop context */
62  break;
63  }
64 
65  if(JJ) jj_add("corr0", corr_to_json(laser_sens->corr, laser_sens->nrays));
66 
67  /* Kill some correspondences (using dubious algorithm) */
68  if(params->outliers_remove_doubles)
69  kill_outliers_double(params);
70 
71  int num_corr2 = ld_num_valid_correspondences(laser_sens);
72 
73  if(JJ) jj_add("corr1", corr_to_json(laser_sens->corr, laser_sens->nrays));
74 
75  double error=0;
76  /* Trim correspondences */
77  kill_outliers_trim(params, &error);
78  int num_corr_after = ld_num_valid_correspondences(laser_sens);
79 
80  if(JJ) {
81  jj_add("corr2", corr_to_json(laser_sens->corr, laser_sens->nrays));
82  jj_add_int("num_corr0", num_corr);
83  jj_add_int("num_corr1", num_corr2);
84  jj_add_int("num_corr2", num_corr_after);
85  }
86 
87  *total_error = error;
88  *valid = num_corr_after;
89 
90  sm_debug(" icp_loop: total error: %f valid %d mean = %f\n", *total_error, *valid, *total_error/ *valid);
91 
92  /* If not many correspondences, bail out */
93  if(num_corr_after < fail_perc * laser_sens->nrays){
94  sm_error(" icp_loop: failed: after trimming, only %d correspondences.\n",num_corr_after);
95  all_is_okay = 0;
96  egsl_pop_named("icp_loop iteration"); /* loop context */
97  break;
98  }
99 
100  /* Compute next estimate based on the correspondences */
101  if(!compute_next_estimate(params, x_old, x_new)) {
102  sm_error(" icp_loop: Cannot compute next estimate.\n");
103  all_is_okay = 0;
104  egsl_pop_named("icp_loop iteration");
105  break;
106  }
107 
108  pose_diff_d(x_new, x_old, delta);
109 
110  {
111  sm_debug(" icp_loop: killing. laser_sens has %d/%d rays valid, %d corr found -> %d after double cut -> %d after adaptive cut \n", count_equal(laser_sens->valid, laser_sens->nrays, 1), laser_sens->nrays, num_corr, num_corr2, num_corr_after);
112  if(JJ) {
113  jj_add_double_array("x_new", x_new, 3);
114  jj_add_double_array("delta", delta, 3);
115  }
116  }
118  hashes[iteration] = ld_corr_hash(laser_sens);
119 
120  {
121  sm_debug(" icp_loop: it. %d hash=%d nvalid=%d mean error = %f, x_new= %s\n",
122  iteration, hashes[iteration], *valid, *total_error/ *valid,
123  friendly_pose(x_new));
124  }
125 
126 
128  if(params->use_point_to_line_distance) {
129  int loop_detected = 0; /* TODO: make function */
130  int a; for(a=iteration-1;a>=0;a--) {
131  if(hashes[a]==hashes[iteration]) {
132  sm_debug("icpc: oscillation detected (cycle length = %d)\n", iteration-a);
133  loop_detected = 1;
134  break;
135  }
136  }
137  if(loop_detected) {
138  egsl_pop_named("icp_loop iteration");
139  break;
140  }
141  }
142 
143  /* This termination criterium is useless when using
144  the point-to-line-distance; however, we put it here because
145  one can choose to use the point-to-point distance. */
146  if(termination_criterion(params, delta)) {
147  egsl_pop_named("icp_loop iteration");
148  break;
149  }
150 
151  copy_d(x_new, 3, x_old);
152  copy_d(delta, 3, delta_old);
153 
154 
155  egsl_pop_named("icp_loop iteration");
156  }
157 
158  if(JJ) jj_loop_exit();
159 
160  *iterations = iteration+1;
161 
162  return all_is_okay;
163 }
164 
165 int termination_criterion(struct sm_params*params, const double*delta){
166  double a = norm_d(delta);
167  double b = fabs(delta[2]);
168  return (a<params->epsilon_xy) && (b<params->epsilon_theta);
169 }
170 
172  const double x_old[3], double x_new[3])
173 {
174  LDP laser_ref = params->laser_ref;
175  LDP laser_sens = params->laser_sens;
176 
177  struct gpc_corr c[laser_sens->nrays];
178 
179  int i; int k=0;
180  for(i=0;i<laser_sens->nrays;i++) {
181  if(!laser_sens->valid[i])
182  continue;
183 
184  if(!ld_valid_corr(laser_sens,i))
185  continue;
186 
187  int j1 = laser_sens->corr[i].j1;
188  int j2 = laser_sens->corr[i].j2;
189 
190  c[k].valid = 1;
191 
192  if(laser_sens->corr[i].type == corr_pl) {
193 
194  c[k].p[0] = laser_sens->points[i].p[0];
195  c[k].p[1] = laser_sens->points[i].p[1];
196  c[k].q[0] = laser_ref->points[j1].p[0];
197  c[k].q[1] = laser_ref->points[j1].p[1];
198 
200  double diff[2];
201  diff[0] = laser_ref->points[j1].p[0]-laser_ref->points[j2].p[0];
202  diff[1] = laser_ref->points[j1].p[1]-laser_ref->points[j2].p[1];
203  double one_on_norm = 1 / sqrt(diff[0]*diff[0]+diff[1]*diff[1]);
204  double normal[2];
205  normal[0] = +diff[1] * one_on_norm;
206  normal[1] = -diff[0] * one_on_norm;
207 
208  double cos_alpha = normal[0];
209  double sin_alpha = normal[1];
210 
211  c[k].C[0][0] = cos_alpha*cos_alpha;
212  c[k].C[1][0] =
213  c[k].C[0][1] = cos_alpha*sin_alpha;
214  c[k].C[1][1] = sin_alpha*sin_alpha;
215 
216 /* sm_debug("k=%d, i=%d sens_phi: %fdeg, j1=%d j2=%d, alpha_seg=%f, cos=%f sin=%f \n", k,i,
217  rad2deg(laser_sens->theta[i]), j1,j2, atan2(sin_alpha,cos_alpha), cos_alpha,sin_alpha);*/
218 
219 #if 0
220  /* Note: it seems that because of numerical errors this matrix might be
221  not semidef positive. */
222  double det = c[k].C[0][0] * c[k].C[1][1] - c[k].C[0][1] * c[k].C[1][0];
223  double trace = c[k].C[0][0] + c[k].C[1][1];
224 
225  int semidef = (det >= 0) && (trace>0);
226  if(!semidef) {
227  /* printf("%d: Adjusting correspondence weights\n",i);*/
228  double eps = -det;
229  c[k].C[0][0] += 2*sqrt(eps);
230  c[k].C[1][1] += 2*sqrt(eps);
231  }
232 #endif
233  } else {
234  c[k].p[0] = laser_sens->points[i].p[0];
235  c[k].p[1] = laser_sens->points[i].p[1];
236 
238  laser_ref->points[j1].p,
239  laser_ref->points[j2].p,
240  laser_sens->points_w[i].p,
241  c[k].q);
242 
243  /* Identity matrix */
244  c[k].C[0][0] = 1;
245  c[k].C[1][0] = 0;
246  c[k].C[0][1] = 0;
247  c[k].C[1][1] = 1;
248  }
249 
250 
251  double factor = 1;
252 
253  /* Scale the correspondence weight by a factor concerning the
254  information in this reading. */
255  if(params->use_ml_weights) {
256  int have_alpha = 0;
257  double alpha = 0;
258  if(!is_nan(laser_ref->true_alpha[j1])) {
259  alpha = laser_ref->true_alpha[j1];
260  have_alpha = 1;
261  } else if(laser_ref->alpha_valid[j1]) {
262  alpha = laser_ref->alpha[j1];;
263  have_alpha = 1;
264  } else have_alpha = 0;
265 
266  if(have_alpha) {
267  double pose_theta = x_old[2];
272  double beta = alpha - (pose_theta + laser_sens->theta[i]);
273  factor = 1 / square(cos(beta));
274  } else {
275  static int warned_before = 0;
276  if(!warned_before) {
277  sm_error("Param use_ml_weights was active, but not valid alpha[] or true_alpha[]."
278  "Perhaps, if this is a single ray not having alpha, you should mark it as inactive.\n");
279  sm_error("Writing laser_ref: \n");
280  ld_write_as_json(laser_ref, stderr);
281  warned_before = 1;
282  }
283  }
284  }
285 
286  /* Weight the points by the sigma in laser_sens */
287  if(params->use_sigma_weights) {
288  if(!is_nan(laser_sens->readings_sigma[i])) {
289  factor *= 1 / square(laser_sens->readings_sigma[i]);
290  } else {
291  static int warned_before = 0;
292  if(!warned_before) {
293  sm_error("Param use_sigma_weights was active, but the field readings_sigma[] was not filled in.\n");
294  sm_error("Writing laser_sens: \n");
295  ld_write_as_json(laser_sens, stderr);
296  }
297  }
298  }
299 
300  c[k].C[0][0] *= factor;
301  c[k].C[1][0] *= factor;
302  c[k].C[0][1] *= factor;
303  c[k].C[1][1] *= factor;
304 
305  k++;
306  }
307 
308  /* TODO: use prior for odometry */
309  double std = 0.11;
310  const double inv_cov_x0[9] =
311  {1/(std*std), 0, 0,
312  0, 1/(std*std), 0,
313  0, 0, 0};
314 
315 
316  int ok = gpc_solve(k, c, 0, inv_cov_x0, x_new);
317  if(!ok) {
318  sm_error("gpc_solve_valid failed\n");
319  return 0;
320  }
321 
322  double old_error = gpc_total_error(c, k, x_old);
323  double new_error = gpc_total_error(c, k, x_new);
324 
325  sm_debug("\tcompute_next_estimate: old error: %f x_old= %s \n", old_error, friendly_pose(x_old));
326  sm_debug("\tcompute_next_estimate: new error: %f x_new= %s \n", new_error, friendly_pose(x_new));
327  sm_debug("\tcompute_next_estimate: new error - old_error: %g \n", new_error-old_error);
328 
329  double epsilon = 0.000001;
330  if(new_error > old_error + epsilon) {
331  sm_error("\tcompute_next_estimate: something's fishy here! Old error: %lf new error: %lf x_old %lf %lf %lf x_new %lf %lf %lf\n",old_error,new_error,x_old[0],x_old[1],x_old[2],x_new[0],x_new[1],x_new[2]);
332  }
333 
334  return 1;
335 }
336 
337 
338 
void debug_correspondences(struct sm_params *params)
Definition: icp_debug.c:4
int *restrict valid
Definition: laser_data.h:23
double norm_d(const double p[2])
Definition: math_utils.c:71
void jj_add_int(const char *name, int v)
Definition: json_journal.c:86
point2d *restrict points
Definition: laser_data.h:44
int outliers_remove_doubles
Definition: algos.h:69
double C[2][2]
Definition: gpc.h:27
void ld_write_as_json(LDP ld, FILE *stream)
void copy_d(const double *from, int n, double *to)
Definition: math_utils.c:83
int use_ml_weights
Definition: algos.h:107
int max_iterations
Definition: algos.h:27
const char * friendly_pose(const double *pose)
Definition: math_utils.c:266
double p[2]
Definition: gpc.h:24
INLINE int ld_valid_corr(LDP ld, int i)
Definition: gpc.h:23
int compute_next_estimate(struct sm_params *params, const double x_old[3], double x_new[3])
Definition: icp_loop.c:171
void jj_loop_enter(const char *loop_name)
Definition: json_journal.c:61
void kill_outliers_trim(struct sm_params *params, double *total_error)
Definition: icp_outliers.c:83
#define JJ
Definition: json_journal.h:21
int termination_criterion(struct sm_params *params, const double *delta)
Definition: icp_loop.c:165
double *restrict true_alpha
Definition: laser_data.h:34
int use_corr_tricks
Definition: algos.h:36
int use_sigma_weights
Definition: algos.h:110
void find_correspondences(struct sm_params *params)
Definition: icp_corr_dumb.c:30
int count_equal(const int *v, int n, int value)
Definition: math_utils.c:192
int *restrict alpha_valid
Definition: laser_data.h:30
int icp_loop(struct sm_params *params, const double *q0, double *x_new, double *total_error, int *valid, int *iterations)
Definition: icp_loop.c:13
int valid
Definition: gpc.h:29
void kill_outliers_double(struct sm_params *params)
Definition: icp_outliers.c:42
LDP laser_ref
Definition: algos.h:14
LDP laser_sens
Definition: algos.h:16
void jj_add(const char *name, JO jo)
Definition: json_journal.c:104
double q[2]
Definition: gpc.h:25
void egsl_push_named(const char *name)
Definition: egsl.c:91
struct correspondence *restrict corr
Definition: laser_data.h:36
unsigned int ld_corr_hash(LDP ld)
Definition: laser_data.c:267
void jj_loop_exit()
Definition: json_journal.c:78
void ld_compute_world_coords(LDP ld, const double *pose)
Definition: laser_data.c:133
void jj_loop_iteration()
Definition: json_journal.c:68
void jj_add_double_array(const char *name, double *v, int n)
Definition: json_journal.c:96
int is_nan(double v)
Definition: math_utils.c:60
JO corr_to_json(struct correspondence *corr, int n)
void find_correspondences_tricks(struct sm_params *params)
void sm_debug(const char *msg,...)
Definition: logging.c:88
int any_nan(const double *d, int n)
Definition: math_utils.c:64
void pose_diff_d(const double pose2[3], const double pose1[3], double res[3])
Definition: math_utils.c:115
double epsilon_theta
Definition: algos.h:31
int gpc_solve(int K, const struct gpc_corr *c, const double *x0, const double *cov_x0, double *x_out)
Definition: gpc.c:29
void projection_on_segment_d(const double a[2], const double b[2], const double x[2], double proj[2])
Definition: math_utils.c:156
double square(double x)
Definition: math_utils.c:124
int ld_num_valid_correspondences(LDP ld)
Definition: laser_data.c:168
double *restrict alpha
Definition: laser_data.h:28
int use_point_to_line_distance
Definition: algos.h:99
void sm_error(const char *msg,...)
Definition: logging.c:49
double gpc_total_error(const struct gpc_corr *co, int n, const double *x)
Definition: gpc.c:301
double p[2]
Definition: laser_data.h:12
void egsl_pop_named(const char *name)
Definition: egsl.c:117
int debug_verify_tricks
Definition: algos.h:117


csm
Author(s): Andrea Censi
autogenerated on Tue May 11 2021 02:18:23