pf.c
Go to the documentation of this file.
1 /*
2  * Player - One Hell of a Robot Server
3  * Copyright (C) 2000 Brian Gerkey & Kasper Stoy
4  * gerkey@usc.edu kaspers@robotics.usc.edu
5  *
6  * This library is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU Lesser General Public
8  * License as published by the Free Software Foundation; either
9  * version 2.1 of the License, or (at your option) any later version.
10  *
11  * This library is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14  * Lesser General Public License for more details.
15  *
16  * You should have received a copy of the GNU Lesser General Public
17  * License along with this library; if not, write to the Free Software
18  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
19  *
20  */
21 /**************************************************************************
22  * Desc: Simple particle filter for localization.
23  * Author: Andrew Howard
24  * Date: 10 Dec 2002
25  * CVS: $Id: pf.c 6345 2008-04-17 01:36:39Z gerkey $
26  *************************************************************************/
27 
28 #include <assert.h>
29 #include <math.h>
30 #include <stdlib.h>
31 #include <time.h>
32 
33 #include "amcl/pf/pf.h"
34 #include "amcl/pf/pf_pdf.h"
35 #include "amcl/pf/pf_kdtree.h"
36 
37 
38 // Compute the required number of samples, given that there are k bins
39 // with samples in them.
40 static int pf_resample_limit(pf_t *pf, int k);
41 
42 
43 
44 // Create a new filter
45 pf_t *pf_alloc(int min_samples, int max_samples,
46  double alpha_slow, double alpha_fast,
47  pf_init_model_fn_t random_pose_fn, void *random_pose_data)
48 {
49  int i, j;
50  pf_t *pf;
51  pf_sample_set_t *set;
52  pf_sample_t *sample;
53 
54  srand48(time(NULL));
55 
56  pf = calloc(1, sizeof(pf_t));
57 
58  pf->random_pose_fn = random_pose_fn;
59  pf->random_pose_data = random_pose_data;
60 
61  pf->min_samples = min_samples;
62  pf->max_samples = max_samples;
63 
64  // Control parameters for the population size calculation. [err] is
65  // the max error between the true distribution and the estimated
66  // distribution. [z] is the upper standard normal quantile for (1 -
67  // p), where p is the probability that the error on the estimated
68  // distrubition will be less than [err].
69  pf->pop_err = 0.01;
70  pf->pop_z = 3;
71  pf->dist_threshold = 0.5;
72 
73  pf->current_set = 0;
74  for (j = 0; j < 2; j++)
75  {
76  set = pf->sets + j;
77 
78  set->sample_count = max_samples;
79  set->samples = calloc(max_samples, sizeof(pf_sample_t));
80 
81  for (i = 0; i < set->sample_count; i++)
82  {
83  sample = set->samples + i;
84  sample->pose.v[0] = 0.0;
85  sample->pose.v[1] = 0.0;
86  sample->pose.v[2] = 0.0;
87  sample->weight = 1.0 / max_samples;
88  }
89 
90  // HACK: is 3 times max_samples enough?
91  set->kdtree = pf_kdtree_alloc(3 * max_samples);
92 
93  set->cluster_count = 0;
94  set->cluster_max_count = max_samples;
95  set->clusters = calloc(set->cluster_max_count, sizeof(pf_cluster_t));
96 
97  set->mean = pf_vector_zero();
98  set->cov = pf_matrix_zero();
99  }
100 
101  pf->w_slow = 0.0;
102  pf->w_fast = 0.0;
103 
104  pf->alpha_slow = alpha_slow;
105  pf->alpha_fast = alpha_fast;
106 
107  //set converged to 0
108  pf_init_converged(pf);
109 
110  return pf;
111 }
112 
113 // Free an existing filter
114 void pf_free(pf_t *pf)
115 {
116  int i;
117 
118  for (i = 0; i < 2; i++)
119  {
120  free(pf->sets[i].clusters);
121  pf_kdtree_free(pf->sets[i].kdtree);
122  free(pf->sets[i].samples);
123  }
124  free(pf);
125 
126  return;
127 }
128 
129 // Initialize the filter using a guassian
130 void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov)
131 {
132  int i;
133  pf_sample_set_t *set;
134  pf_sample_t *sample;
135  pf_pdf_gaussian_t *pdf;
136 
137  set = pf->sets + pf->current_set;
138 
139  // Create the kd tree for adaptive sampling
140  pf_kdtree_clear(set->kdtree);
141 
142  set->sample_count = pf->max_samples;
143 
144  pdf = pf_pdf_gaussian_alloc(mean, cov);
145 
146  // Compute the new sample poses
147  for (i = 0; i < set->sample_count; i++)
148  {
149  sample = set->samples + i;
150  sample->weight = 1.0 / pf->max_samples;
151  sample->pose = pf_pdf_gaussian_sample(pdf);
152 
153  // Add sample to histogram
154  pf_kdtree_insert(set->kdtree, sample->pose, sample->weight);
155  }
156 
157  pf->w_slow = pf->w_fast = 0.0;
158 
160 
161  // Re-compute cluster statistics
162  pf_cluster_stats(pf, set);
163 
164  //set converged to 0
165  pf_init_converged(pf);
166 
167  return;
168 }
169 
170 
171 // Initialize the filter using some model
172 void pf_init_model(pf_t *pf, pf_init_model_fn_t init_fn, void *init_data)
173 {
174  int i;
175  pf_sample_set_t *set;
176  pf_sample_t *sample;
177 
178  set = pf->sets + pf->current_set;
179 
180  // Create the kd tree for adaptive sampling
181  pf_kdtree_clear(set->kdtree);
182 
183  set->sample_count = pf->max_samples;
184 
185  // Compute the new sample poses
186  for (i = 0; i < set->sample_count; i++)
187  {
188  sample = set->samples + i;
189  sample->weight = 1.0 / pf->max_samples;
190  sample->pose = (*init_fn) (init_data);
191 
192  // Add sample to histogram
193  pf_kdtree_insert(set->kdtree, sample->pose, sample->weight);
194  }
195 
196  pf->w_slow = pf->w_fast = 0.0;
197 
198  // Re-compute cluster statistics
199  pf_cluster_stats(pf, set);
200 
201  //set converged to 0
202  pf_init_converged(pf);
203 
204  return;
205 }
206 
208  pf_sample_set_t *set;
209  set = pf->sets + pf->current_set;
210  set->converged = 0;
211  pf->converged = 0;
212 }
213 
215 {
216  int i;
217  pf_sample_set_t *set;
218  pf_sample_t *sample;
219  double total;
220 
221  set = pf->sets + pf->current_set;
222  double mean_x = 0, mean_y = 0;
223 
224  for (i = 0; i < set->sample_count; i++){
225  sample = set->samples + i;
226 
227  mean_x += sample->pose.v[0];
228  mean_y += sample->pose.v[1];
229  }
230  mean_x /= set->sample_count;
231  mean_y /= set->sample_count;
232 
233  for (i = 0; i < set->sample_count; i++){
234  sample = set->samples + i;
235  if(fabs(sample->pose.v[0] - mean_x) > pf->dist_threshold ||
236  fabs(sample->pose.v[1] - mean_y) > pf->dist_threshold){
237  set->converged = 0;
238  pf->converged = 0;
239  return 0;
240  }
241  }
242  set->converged = 1;
243  pf->converged = 1;
244  return 1;
245 }
246 
247 // Update the filter with some new action
248 void pf_update_action(pf_t *pf, pf_action_model_fn_t action_fn, void *action_data)
249 {
250  pf_sample_set_t *set;
251 
252  set = pf->sets + pf->current_set;
253 
254  (*action_fn) (action_data, set);
255 
256  return;
257 }
258 
259 
260 #include <float.h>
261 // Update the filter with some new sensor observation
262 void pf_update_sensor(pf_t *pf, pf_sensor_model_fn_t sensor_fn, void *sensor_data)
263 {
264  int i;
265  pf_sample_set_t *set;
266  pf_sample_t *sample;
267  double total;
268 
269  set = pf->sets + pf->current_set;
270 
271  // Compute the sample weights
272  total = (*sensor_fn) (sensor_data, set);
273 
274  if (total > 0.0)
275  {
276  // Normalize weights
277  double w_avg=0.0;
278  for (i = 0; i < set->sample_count; i++)
279  {
280  sample = set->samples + i;
281  w_avg += sample->weight;
282  sample->weight /= total;
283  }
284  // Update running averages of likelihood of samples (Prob Rob p258)
285  w_avg /= set->sample_count;
286  if(pf->w_slow == 0.0)
287  pf->w_slow = w_avg;
288  else
289  pf->w_slow += pf->alpha_slow * (w_avg - pf->w_slow);
290  if(pf->w_fast == 0.0)
291  pf->w_fast = w_avg;
292  else
293  pf->w_fast += pf->alpha_fast * (w_avg - pf->w_fast);
294  //printf("w_avg: %e slow: %e fast: %e\n",
295  //w_avg, pf->w_slow, pf->w_fast);
296  }
297  else
298  {
299  // Handle zero total
300  for (i = 0; i < set->sample_count; i++)
301  {
302  sample = set->samples + i;
303  sample->weight = 1.0 / set->sample_count;
304  }
305  }
306 
307  return;
308 }
309 
310 
311 // Resample the distribution
313 {
314  int i;
315  double total;
316  pf_sample_set_t *set_a, *set_b;
317  pf_sample_t *sample_a, *sample_b;
318 
319  //double r,c,U;
320  //int m;
321  //double count_inv;
322  double* c;
323 
324  double w_diff;
325 
326  set_a = pf->sets + pf->current_set;
327  set_b = pf->sets + (pf->current_set + 1) % 2;
328 
329  // Build up cumulative probability table for resampling.
330  // TODO: Replace this with a more efficient procedure
331  // (e.g., http://www.network-theory.co.uk/docs/gslref/GeneralDiscreteDistributions.html)
332  c = (double*)malloc(sizeof(double)*(set_a->sample_count+1));
333  c[0] = 0.0;
334  for(i=0;i<set_a->sample_count;i++)
335  c[i+1] = c[i]+set_a->samples[i].weight;
336 
337  // Create the kd tree for adaptive sampling
338  pf_kdtree_clear(set_b->kdtree);
339 
340  // Draw samples from set a to create set b.
341  total = 0;
342  set_b->sample_count = 0;
343 
344  w_diff = 1.0 - pf->w_fast / pf->w_slow;
345  if(w_diff < 0.0)
346  w_diff = 0.0;
347  //printf("w_diff: %9.6f\n", w_diff);
348 
349  // Can't (easily) combine low-variance sampler with KLD adaptive
350  // sampling, so we'll take the more traditional route.
351  /*
352  // Low-variance resampler, taken from Probabilistic Robotics, p110
353  count_inv = 1.0/set_a->sample_count;
354  r = drand48() * count_inv;
355  c = set_a->samples[0].weight;
356  i = 0;
357  m = 0;
358  */
359  while(set_b->sample_count < pf->max_samples)
360  {
361  sample_b = set_b->samples + set_b->sample_count++;
362 
363  if(drand48() < w_diff)
364  sample_b->pose = (pf->random_pose_fn)(pf->random_pose_data);
365  else
366  {
367  // Can't (easily) combine low-variance sampler with KLD adaptive
368  // sampling, so we'll take the more traditional route.
369  /*
370  // Low-variance resampler, taken from Probabilistic Robotics, p110
371  U = r + m * count_inv;
372  while(U>c)
373  {
374  i++;
375  // Handle wrap-around by resetting counters and picking a new random
376  // number
377  if(i >= set_a->sample_count)
378  {
379  r = drand48() * count_inv;
380  c = set_a->samples[0].weight;
381  i = 0;
382  m = 0;
383  U = r + m * count_inv;
384  continue;
385  }
386  c += set_a->samples[i].weight;
387  }
388  m++;
389  */
390 
391  // Naive discrete event sampler
392  double r;
393  r = drand48();
394  for(i=0;i<set_a->sample_count;i++)
395  {
396  if((c[i] <= r) && (r < c[i+1]))
397  break;
398  }
399  assert(i<set_a->sample_count);
400 
401  sample_a = set_a->samples + i;
402 
403  assert(sample_a->weight > 0);
404 
405  // Add sample to list
406  sample_b->pose = sample_a->pose;
407  }
408 
409  sample_b->weight = 1.0;
410  total += sample_b->weight;
411 
412  // Add sample to histogram
413  pf_kdtree_insert(set_b->kdtree, sample_b->pose, sample_b->weight);
414 
415  // See if we have enough samples yet
416  if (set_b->sample_count > pf_resample_limit(pf, set_b->kdtree->leaf_count))
417  break;
418  }
419 
420  // Reset averages, to avoid spiraling off into complete randomness.
421  if(w_diff > 0.0)
422  pf->w_slow = pf->w_fast = 0.0;
423 
424  //fprintf(stderr, "\n\n");
425 
426  // Normalize weights
427  for (i = 0; i < set_b->sample_count; i++)
428  {
429  sample_b = set_b->samples + i;
430  sample_b->weight /= total;
431  }
432 
433  // Re-compute cluster statistics
434  pf_cluster_stats(pf, set_b);
435 
436  // Use the newly created sample set
437  pf->current_set = (pf->current_set + 1) % 2;
438 
440 
441  free(c);
442  return;
443 }
444 
445 
446 // Compute the required number of samples, given that there are k bins
447 // with samples in them. This is taken directly from Fox et al.
448 int pf_resample_limit(pf_t *pf, int k)
449 {
450  double a, b, c, x;
451  int n;
452 
453  if (k <= 1)
454  return pf->max_samples;
455 
456  a = 1;
457  b = 2 / (9 * ((double) k - 1));
458  c = sqrt(2 / (9 * ((double) k - 1))) * pf->pop_z;
459  x = a - b + c;
460 
461  n = (int) ceil((k - 1) / (2 * pf->pop_err) * x * x * x);
462 
463  if (n < pf->min_samples)
464  return pf->min_samples;
465  if (n > pf->max_samples)
466  return pf->max_samples;
467 
468  return n;
469 }
470 
471 
472 // Re-compute the cluster statistics for a sample set
474 {
475  int i, j, k, cidx;
476  pf_sample_t *sample;
477  pf_cluster_t *cluster;
478 
479  // Workspace
480  double m[4], c[2][2];
481  size_t count;
482  double weight;
483 
484  // Cluster the samples
485  pf_kdtree_cluster(set->kdtree);
486 
487  // Initialize cluster stats
488  set->cluster_count = 0;
489 
490  for (i = 0; i < set->cluster_max_count; i++)
491  {
492  cluster = set->clusters + i;
493  cluster->count = 0;
494  cluster->weight = 0;
495  cluster->mean = pf_vector_zero();
496  cluster->cov = pf_matrix_zero();
497 
498  for (j = 0; j < 4; j++)
499  cluster->m[j] = 0.0;
500  for (j = 0; j < 2; j++)
501  for (k = 0; k < 2; k++)
502  cluster->c[j][k] = 0.0;
503  }
504 
505  // Initialize overall filter stats
506  count = 0;
507  weight = 0.0;
508  set->mean = pf_vector_zero();
509  set->cov = pf_matrix_zero();
510  for (j = 0; j < 4; j++)
511  m[j] = 0.0;
512  for (j = 0; j < 2; j++)
513  for (k = 0; k < 2; k++)
514  c[j][k] = 0.0;
515 
516  // Compute cluster stats
517  for (i = 0; i < set->sample_count; i++)
518  {
519  sample = set->samples + i;
520 
521  //printf("%d %f %f %f\n", i, sample->pose.v[0], sample->pose.v[1], sample->pose.v[2]);
522 
523  // Get the cluster label for this sample
524  cidx = pf_kdtree_get_cluster(set->kdtree, sample->pose);
525  assert(cidx >= 0);
526  if (cidx >= set->cluster_max_count)
527  continue;
528  if (cidx + 1 > set->cluster_count)
529  set->cluster_count = cidx + 1;
530 
531  cluster = set->clusters + cidx;
532 
533  cluster->count += 1;
534  cluster->weight += sample->weight;
535 
536  count += 1;
537  weight += sample->weight;
538 
539  // Compute mean
540  cluster->m[0] += sample->weight * sample->pose.v[0];
541  cluster->m[1] += sample->weight * sample->pose.v[1];
542  cluster->m[2] += sample->weight * cos(sample->pose.v[2]);
543  cluster->m[3] += sample->weight * sin(sample->pose.v[2]);
544 
545  m[0] += sample->weight * sample->pose.v[0];
546  m[1] += sample->weight * sample->pose.v[1];
547  m[2] += sample->weight * cos(sample->pose.v[2]);
548  m[3] += sample->weight * sin(sample->pose.v[2]);
549 
550  // Compute covariance in linear components
551  for (j = 0; j < 2; j++)
552  for (k = 0; k < 2; k++)
553  {
554  cluster->c[j][k] += sample->weight * sample->pose.v[j] * sample->pose.v[k];
555  c[j][k] += sample->weight * sample->pose.v[j] * sample->pose.v[k];
556  }
557  }
558 
559  // Normalize
560  for (i = 0; i < set->cluster_count; i++)
561  {
562  cluster = set->clusters + i;
563 
564  cluster->mean.v[0] = cluster->m[0] / cluster->weight;
565  cluster->mean.v[1] = cluster->m[1] / cluster->weight;
566  cluster->mean.v[2] = atan2(cluster->m[3], cluster->m[2]);
567 
568  cluster->cov = pf_matrix_zero();
569 
570  // Covariance in linear components
571  for (j = 0; j < 2; j++)
572  for (k = 0; k < 2; k++)
573  cluster->cov.m[j][k] = cluster->c[j][k] / cluster->weight -
574  cluster->mean.v[j] * cluster->mean.v[k];
575 
576  // Covariance in angular components; I think this is the correct
577  // formula for circular statistics.
578  cluster->cov.m[2][2] = -2 * log(sqrt(cluster->m[2] * cluster->m[2] +
579  cluster->m[3] * cluster->m[3]));
580 
581  //printf("cluster %d %d %f (%f %f %f)\n", i, cluster->count, cluster->weight,
582  //cluster->mean.v[0], cluster->mean.v[1], cluster->mean.v[2]);
583  //pf_matrix_fprintf(cluster->cov, stdout, "%e");
584  }
585 
586  // Compute overall filter stats
587  set->mean.v[0] = m[0] / weight;
588  set->mean.v[1] = m[1] / weight;
589  set->mean.v[2] = atan2(m[3], m[2]);
590 
591  // Covariance in linear components
592  for (j = 0; j < 2; j++)
593  for (k = 0; k < 2; k++)
594  set->cov.m[j][k] = c[j][k] / weight - set->mean.v[j] * set->mean.v[k];
595 
596  // Covariance in angular components; I think this is the correct
597  // formula for circular statistics.
598  set->cov.m[2][2] = -2 * log(sqrt(m[2] * m[2] + m[3] * m[3]));
599 
600  return;
601 }
602 
603 
604 // Compute the CEP statistics (mean and variance).
605 void pf_get_cep_stats(pf_t *pf, pf_vector_t *mean, double *var)
606 {
607  int i;
608  double mn, mx, my, mrr;
609  pf_sample_set_t *set;
610  pf_sample_t *sample;
611 
612  set = pf->sets + pf->current_set;
613 
614  mn = 0.0;
615  mx = 0.0;
616  my = 0.0;
617  mrr = 0.0;
618 
619  for (i = 0; i < set->sample_count; i++)
620  {
621  sample = set->samples + i;
622 
623  mn += sample->weight;
624  mx += sample->weight * sample->pose.v[0];
625  my += sample->weight * sample->pose.v[1];
626  mrr += sample->weight * sample->pose.v[0] * sample->pose.v[0];
627  mrr += sample->weight * sample->pose.v[1] * sample->pose.v[1];
628  }
629 
630  mean->v[0] = mx / mn;
631  mean->v[1] = my / mn;
632  mean->v[2] = 0.0;
633 
634  *var = mrr / mn - (mx * mx / (mn * mn) + my * my / (mn * mn));
635 
636  return;
637 }
638 
639 
640 // Get the statistics for a particular cluster.
641 int pf_get_cluster_stats(pf_t *pf, int clabel, double *weight,
642  pf_vector_t *mean, pf_matrix_t *cov)
643 {
644  pf_sample_set_t *set;
645  pf_cluster_t *cluster;
646 
647  set = pf->sets + pf->current_set;
648 
649  if (clabel >= set->cluster_count)
650  return 0;
651  cluster = set->clusters + clabel;
652 
653  *weight = cluster->weight;
654  *mean = cluster->mean;
655  *cov = cluster->cov;
656 
657  return 1;
658 }
659 
660 
double w_slow
Definition: pf.h:125
pf_init_model_fn_t random_pose_fn
Definition: pf.h:131
double(* pf_sensor_model_fn_t)(void *sensor_data, struct _pf_sample_set_t *set)
Definition: pf.h:54
static int pf_resample_limit(pf_t *pf, int k)
Definition: pf.c:448
void pf_update_sensor(pf_t *pf, pf_sensor_model_fn_t sensor_fn, void *sensor_data)
Definition: pf.c:262
double pop_err
Definition: pf.h:117
void pf_get_cep_stats(pf_t *pf, pf_vector_t *mean, double *var)
Definition: pf.c:605
double v[3]
Definition: pf_vector.h:40
void pf_kdtree_clear(pf_kdtree_t *self)
Definition: pf_kdtree.c:100
void pf_kdtree_insert(pf_kdtree_t *self, pf_vector_t pose, double value)
Definition: pf_kdtree.c:112
Definition: pf.h:111
pf_vector_t(* pf_init_model_fn_t)(void *init_data)
Definition: pf.h:45
pf_matrix_t cov
Definition: pf.h:81
void pf_init_converged(pf_t *pf)
Definition: pf.c:207
pf_vector_t pf_vector_zero()
Definition: pf_vector.c:38
pf_kdtree_t * kdtree
Definition: pf.h:97
static int n
Definition: eig3.c:12
double dist_threshold
Definition: pf.h:134
void pf_update_resample(pf_t *pf)
Definition: pf.c:312
pf_t * pf_alloc(int min_samples, int max_samples, double alpha_slow, double alpha_fast, pf_init_model_fn_t random_pose_fn, void *random_pose_data)
Definition: pf.c:45
void pf_init_model(pf_t *pf, pf_init_model_fn_t init_fn, void *init_data)
Definition: pf.c:172
void pf_kdtree_free(pf_kdtree_t *self)
Definition: pf_kdtree.c:90
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
int max_samples
Definition: pf.h:114
double weight
Definition: pf.h:77
double w_fast
Definition: pf.h:125
int min_samples
Definition: pf.h:114
double pop_z
Definition: pf.h:117
void pf_pdf_gaussian_free(pf_pdf_gaussian_t *pdf)
Definition: pf_pdf.c:74
int current_set
Definition: pf.h:121
Definition: pf.h:59
void pf_update_action(pf_t *pf, pf_action_model_fn_t action_fn, void *action_data)
Definition: pf.c:248
void * random_pose_data
Definition: pf.h:132
int pf_update_converged(pf_t *pf)
Definition: pf.c:214
double m[4]
Definition: pf.h:84
double m[3][3]
Definition: pf_vector.h:47
pf_sample_t * samples
Definition: pf.h:94
pf_matrix_t pf_matrix_zero()
Definition: pf_vector.c:134
TFSIMD_FORCE_INLINE const tfScalar & x() const
int leaf_count
Definition: pf_kdtree.h:75
pf_pdf_gaussian_t * pf_pdf_gaussian_alloc(pf_vector_t x, pf_matrix_t cx)
Definition: pf_pdf.c:46
void pf_cluster_stats(pf_t *pf, pf_sample_set_t *set)
Definition: pf.c:473
void pf_free(pf_t *pf)
Definition: pf.c:114
double alpha_fast
Definition: pf.h:128
pf_vector_t pose
Definition: pf.h:62
void(* pf_action_model_fn_t)(void *action_data, struct _pf_sample_set_t *set)
Definition: pf.h:49
int pf_get_cluster_stats(pf_t *pf, int clabel, double *weight, pf_vector_t *mean, pf_matrix_t *cov)
Definition: pf.c:641
int sample_count
Definition: pf.h:93
double weight
Definition: pf.h:65
void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov)
Definition: pf.c:130
pf_vector_t mean
Definition: pf.h:80
pf_kdtree_t * pf_kdtree_alloc(int max_size)
Definition: pf_kdtree.c:66
pf_cluster_t * clusters
Definition: pf.h:101
int converged
Definition: pf.h:135
pf_sample_set_t sets[2]
Definition: pf.h:122
int pf_kdtree_get_cluster(pf_kdtree_t *self, pf_vector_t pose)
Definition: pf_kdtree.c:168
double alpha_slow
Definition: pf.h:128
double c[2][2]
Definition: pf.h:84
void pf_kdtree_cluster(pf_kdtree_t *self)
Definition: pf_kdtree.c:358
pf_vector_t pf_pdf_gaussian_sample(pf_pdf_gaussian_t *pdf)
Definition: pf_pdf.c:105
int count
Definition: pf.h:74


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:09