pf.c
Go to the documentation of this file.
00001 /*
00002  *  Player - One Hell of a Robot Server
00003  *  Copyright (C) 2000  Brian Gerkey   &  Kasper Stoy
00004  *                      gerkey@usc.edu    kaspers@robotics.usc.edu
00005  *
00006  *  This library is free software; you can redistribute it and/or
00007  *  modify it under the terms of the GNU Lesser General Public
00008  *  License as published by the Free Software Foundation; either
00009  *  version 2.1 of the License, or (at your option) any later version.
00010  *
00011  *  This library is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00014  *  Lesser General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU Lesser General Public
00017  *  License along with this library; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 /**************************************************************************
00022  * Desc: Simple particle filter for localization.
00023  * Author: Andrew Howard
00024  * Date: 10 Dec 2002
00025  * CVS: $Id: pf.c 6345 2008-04-17 01:36:39Z gerkey $
00026  *************************************************************************/
00027 
00028 #include <assert.h>
00029 #include <math.h>
00030 #include <stdlib.h>
00031 #include <time.h>
00032 
00033 #include "pf.h"
00034 #include "pf_pdf.h"
00035 #include "pf_kdtree.h"
00036 
00037 
00038 // Compute the required number of samples, given that there are k bins
00039 // with samples in them.
00040 static int pf_resample_limit(pf_t *pf, int k);
00041 
00042 
00043 
00044 // Create a new filter
00045 pf_t *pf_alloc(int min_samples, int max_samples,
00046                double alpha_slow, double alpha_fast,
00047                pf_init_model_fn_t random_pose_fn, void *random_pose_data)
00048 {
00049   int i, j;
00050   pf_t *pf;
00051   pf_sample_set_t *set;
00052   pf_sample_t *sample;
00053   
00054   srand48(time(NULL));
00055 
00056   pf = calloc(1, sizeof(pf_t));
00057 
00058   pf->random_pose_fn = random_pose_fn;
00059   pf->random_pose_data = random_pose_data;
00060 
00061   pf->min_samples = min_samples;
00062   pf->max_samples = max_samples;
00063 
00064   // Control parameters for the population size calculation.  [err] is
00065   // the max error between the true distribution and the estimated
00066   // distribution.  [z] is the upper standard normal quantile for (1 -
00067   // p), where p is the probability that the error on the estimated
00068   // distrubition will be less than [err].
00069   pf->pop_err = 0.01;
00070   pf->pop_z = 3;
00071   pf->dist_threshold = 0.5; 
00072   
00073   pf->current_set = 0;
00074   for (j = 0; j < 2; j++)
00075   {
00076     set = pf->sets + j;
00077       
00078     set->sample_count = max_samples;
00079     set->samples = calloc(max_samples, sizeof(pf_sample_t));
00080 
00081     for (i = 0; i < set->sample_count; i++)
00082     {
00083       sample = set->samples + i;
00084       sample->pose.v[0] = 0.0;
00085       sample->pose.v[1] = 0.0;
00086       sample->pose.v[2] = 0.0;
00087       sample->weight = 1.0 / max_samples;
00088     }
00089 
00090     // HACK: is 3 times max_samples enough?
00091     set->kdtree = pf_kdtree_alloc(3 * max_samples);
00092 
00093     set->cluster_count = 0;
00094     set->cluster_max_count = max_samples;
00095     set->clusters = calloc(set->cluster_max_count, sizeof(pf_cluster_t));
00096 
00097     set->mean = pf_vector_zero();
00098     set->cov = pf_matrix_zero();
00099   }
00100 
00101   pf->w_slow = 0.0;
00102   pf->w_fast = 0.0;
00103 
00104   pf->alpha_slow = alpha_slow;
00105   pf->alpha_fast = alpha_fast;
00106 
00107   //set converged to 0
00108   pf_init_converged(pf);
00109 
00110   return pf;
00111 }
00112 
00113 // Free an existing filter
00114 void pf_free(pf_t *pf)
00115 {
00116   int i;
00117   
00118   for (i = 0; i < 2; i++)
00119   {
00120     free(pf->sets[i].clusters);
00121     pf_kdtree_free(pf->sets[i].kdtree);
00122     free(pf->sets[i].samples);
00123   }
00124   free(pf);
00125   
00126   return;
00127 }
00128 
00129 // Initialize the filter using a guassian
00130 void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov)
00131 {
00132   int i;
00133   pf_sample_set_t *set;
00134   pf_sample_t *sample;
00135   pf_pdf_gaussian_t *pdf;
00136   
00137   set = pf->sets + pf->current_set;
00138   
00139   // Create the kd tree for adaptive sampling
00140   pf_kdtree_clear(set->kdtree);
00141 
00142   set->sample_count = pf->max_samples;
00143 
00144   pdf = pf_pdf_gaussian_alloc(mean, cov);
00145     
00146   // Compute the new sample poses
00147   for (i = 0; i < set->sample_count; i++)
00148   {
00149     sample = set->samples + i;
00150     sample->weight = 1.0 / pf->max_samples;
00151     sample->pose = pf_pdf_gaussian_sample(pdf);
00152 
00153     // Add sample to histogram
00154     pf_kdtree_insert(set->kdtree, sample->pose, sample->weight);
00155   }
00156 
00157   pf->w_slow = pf->w_fast = 0.0;
00158 
00159   pf_pdf_gaussian_free(pdf);
00160     
00161   // Re-compute cluster statistics
00162   pf_cluster_stats(pf, set); 
00163 
00164   //set converged to 0
00165   pf_init_converged(pf);
00166 
00167   return;
00168 }
00169 
00170 
00171 // Initialize the filter using some model
00172 void pf_init_model(pf_t *pf, pf_init_model_fn_t init_fn, void *init_data)
00173 {
00174   int i;
00175   pf_sample_set_t *set;
00176   pf_sample_t *sample;
00177 
00178   set = pf->sets + pf->current_set;
00179 
00180   // Create the kd tree for adaptive sampling
00181   pf_kdtree_clear(set->kdtree);
00182 
00183   set->sample_count = pf->max_samples;
00184 
00185   // Compute the new sample poses
00186   for (i = 0; i < set->sample_count; i++)
00187   {
00188     sample = set->samples + i;
00189     sample->weight = 1.0 / pf->max_samples;
00190     sample->pose = (*init_fn) (init_data);
00191 
00192     // Add sample to histogram
00193     pf_kdtree_insert(set->kdtree, sample->pose, sample->weight);
00194   }
00195 
00196   pf->w_slow = pf->w_fast = 0.0;
00197 
00198   // Re-compute cluster statistics
00199   pf_cluster_stats(pf, set);
00200   
00201   //set converged to 0
00202   pf_init_converged(pf);
00203 
00204   return;
00205 }
00206 
00207 void pf_init_converged(pf_t *pf){
00208   pf_sample_set_t *set;
00209   set = pf->sets + pf->current_set;
00210   set->converged = 0; 
00211   pf->converged = 0; 
00212 }
00213 
00214 int pf_update_converged(pf_t *pf)
00215 {
00216   int i;
00217   pf_sample_set_t *set;
00218   pf_sample_t *sample;
00219   double total;
00220 
00221   set = pf->sets + pf->current_set;
00222   double mean_x = 0, mean_y = 0;
00223 
00224   for (i = 0; i < set->sample_count; i++){
00225     sample = set->samples + i;
00226 
00227     mean_x += sample->pose.v[0];
00228     mean_y += sample->pose.v[1];
00229   }
00230   mean_x /= set->sample_count;
00231   mean_y /= set->sample_count;
00232   
00233   for (i = 0; i < set->sample_count; i++){
00234     sample = set->samples + i;
00235     if(fabs(sample->pose.v[0] - mean_x) > pf->dist_threshold || 
00236        fabs(sample->pose.v[1] - mean_y) > pf->dist_threshold){
00237       set->converged = 0; 
00238       pf->converged = 0; 
00239       return 0;
00240     }
00241   }
00242   set->converged = 1; 
00243   pf->converged = 1; 
00244   return 1; 
00245 }
00246 
00247 // Update the filter with some new action
00248 void pf_update_action(pf_t *pf, pf_action_model_fn_t action_fn, void *action_data)
00249 {
00250   pf_sample_set_t *set;
00251 
00252   set = pf->sets + pf->current_set;
00253 
00254   (*action_fn) (action_data, set);
00255   
00256   return;
00257 }
00258 
00259 
00260 #include <float.h>
00261 // Update the filter with some new sensor observation
00262 void pf_update_sensor(pf_t *pf, pf_sensor_model_fn_t sensor_fn, void *sensor_data)
00263 {
00264   int i;
00265   pf_sample_set_t *set;
00266   pf_sample_t *sample;
00267   double total;
00268 
00269   set = pf->sets + pf->current_set;
00270 
00271   // Compute the sample weights
00272   total = (*sensor_fn) (sensor_data, set);
00273   
00274   if (total > 0.0)
00275   {
00276     // Normalize weights
00277     double w_avg=0.0;
00278     for (i = 0; i < set->sample_count; i++)
00279     {
00280       sample = set->samples + i;
00281       w_avg += sample->weight;
00282       sample->weight /= total;
00283     }
00284     // Update running averages of likelihood of samples (Prob Rob p258)
00285     w_avg /= set->sample_count;
00286     if(pf->w_slow == 0.0)
00287       pf->w_slow = w_avg;
00288     else
00289       pf->w_slow += pf->alpha_slow * (w_avg - pf->w_slow);
00290     if(pf->w_fast == 0.0)
00291       pf->w_fast = w_avg;
00292     else
00293       pf->w_fast += pf->alpha_fast * (w_avg - pf->w_fast);
00294     //printf("w_avg: %e slow: %e fast: %e\n", 
00295            //w_avg, pf->w_slow, pf->w_fast);
00296   }
00297   else
00298   {
00299     // Handle zero total
00300     for (i = 0; i < set->sample_count; i++)
00301     {
00302       sample = set->samples + i;
00303       sample->weight = 1.0 / set->sample_count;
00304     }
00305   }
00306 
00307   return;
00308 }
00309 
00310 
00311 // Resample the distribution
00312 void pf_update_resample(pf_t *pf)
00313 {
00314   int i;
00315   double total;
00316   pf_sample_set_t *set_a, *set_b;
00317   pf_sample_t *sample_a, *sample_b;
00318 
00319   //double r,c,U;
00320   //int m;
00321   //double count_inv;
00322   double* c;
00323 
00324   double w_diff;
00325 
00326   set_a = pf->sets + pf->current_set;
00327   set_b = pf->sets + (pf->current_set + 1) % 2;
00328 
00329   // Build up cumulative probability table for resampling.
00330   // TODO: Replace this with a more efficient procedure
00331   // (e.g., http://www.network-theory.co.uk/docs/gslref/GeneralDiscreteDistributions.html)
00332   c = (double*)malloc(sizeof(double)*(set_a->sample_count+1));
00333   c[0] = 0.0;
00334   for(i=0;i<set_a->sample_count;i++)
00335     c[i+1] = c[i]+set_a->samples[i].weight;
00336 
00337   // Create the kd tree for adaptive sampling
00338   pf_kdtree_clear(set_b->kdtree);
00339   
00340   // Draw samples from set a to create set b.
00341   total = 0;
00342   set_b->sample_count = 0;
00343 
00344   w_diff = 1.0 - pf->w_fast / pf->w_slow;
00345   if(w_diff < 0.0)
00346     w_diff = 0.0;
00347   //printf("w_diff: %9.6f\n", w_diff);
00348 
00349   // Can't (easily) combine low-variance sampler with KLD adaptive
00350   // sampling, so we'll take the more traditional route.
00351   /*
00352   // Low-variance resampler, taken from Probabilistic Robotics, p110
00353   count_inv = 1.0/set_a->sample_count;
00354   r = drand48() * count_inv;
00355   c = set_a->samples[0].weight;
00356   i = 0;
00357   m = 0;
00358   */
00359   while(set_b->sample_count < pf->max_samples)
00360   {
00361     sample_b = set_b->samples + set_b->sample_count++;
00362 
00363     if(drand48() < w_diff)
00364       sample_b->pose = (pf->random_pose_fn)(pf->random_pose_data);
00365     else
00366     {
00367       // Can't (easily) combine low-variance sampler with KLD adaptive
00368       // sampling, so we'll take the more traditional route.
00369       /*
00370       // Low-variance resampler, taken from Probabilistic Robotics, p110
00371       U = r + m * count_inv;
00372       while(U>c)
00373       {
00374         i++;
00375         // Handle wrap-around by resetting counters and picking a new random
00376         // number
00377         if(i >= set_a->sample_count)
00378         {
00379           r = drand48() * count_inv;
00380           c = set_a->samples[0].weight;
00381           i = 0;
00382           m = 0;
00383           U = r + m * count_inv;
00384           continue;
00385         }
00386         c += set_a->samples[i].weight;
00387       }
00388       m++;
00389       */
00390 
00391       // Naive discrete event sampler
00392       double r;
00393       r = drand48();
00394       for(i=0;i<set_a->sample_count;i++)
00395       {
00396         if((c[i] <= r) && (r < c[i+1]))
00397           break;
00398       }
00399       assert(i<set_a->sample_count);
00400 
00401       sample_a = set_a->samples + i;
00402 
00403       assert(sample_a->weight > 0);
00404 
00405       // Add sample to list
00406       sample_b->pose = sample_a->pose;
00407     }
00408 
00409     sample_b->weight = 1.0;
00410     total += sample_b->weight;
00411 
00412     // Add sample to histogram
00413     pf_kdtree_insert(set_b->kdtree, sample_b->pose, sample_b->weight);
00414 
00415     // See if we have enough samples yet
00416     if (set_b->sample_count > pf_resample_limit(pf, set_b->kdtree->leaf_count))
00417       break;
00418   }
00419   
00420   // Reset averages, to avoid spiraling off into complete randomness.
00421   if(w_diff > 0.0)
00422     pf->w_slow = pf->w_fast = 0.0;
00423 
00424   //fprintf(stderr, "\n\n");
00425 
00426   // Normalize weights
00427   for (i = 0; i < set_b->sample_count; i++)
00428   {
00429     sample_b = set_b->samples + i;
00430     sample_b->weight /= total;
00431   }
00432   
00433   // Re-compute cluster statistics
00434   pf_cluster_stats(pf, set_b);
00435 
00436   // Use the newly created sample set
00437   pf->current_set = (pf->current_set + 1) % 2; 
00438 
00439   pf_update_converged(pf);
00440 
00441   free(c);
00442   return;
00443 }
00444 
00445 
00446 // Compute the required number of samples, given that there are k bins
00447 // with samples in them.  This is taken directly from Fox et al.
00448 int pf_resample_limit(pf_t *pf, int k)
00449 {
00450   double a, b, c, x;
00451   int n;
00452 
00453   if (k <= 1)
00454     return pf->max_samples;
00455 
00456   a = 1;
00457   b = 2 / (9 * ((double) k - 1));
00458   c = sqrt(2 / (9 * ((double) k - 1))) * pf->pop_z;
00459   x = a - b + c;
00460 
00461   n = (int) ceil((k - 1) / (2 * pf->pop_err) * x * x * x);
00462 
00463   if (n < pf->min_samples)
00464     return pf->min_samples;
00465   if (n > pf->max_samples)
00466     return pf->max_samples;
00467   
00468   return n;
00469 }
00470 
00471 
00472 // Re-compute the cluster statistics for a sample set
00473 void pf_cluster_stats(pf_t *pf, pf_sample_set_t *set)
00474 {
00475   int i, j, k, cidx;
00476   pf_sample_t *sample;
00477   pf_cluster_t *cluster;
00478   
00479   // Workspace
00480   double m[4], c[2][2];
00481   size_t count;
00482   double weight;
00483 
00484   // Cluster the samples
00485   pf_kdtree_cluster(set->kdtree);
00486   
00487   // Initialize cluster stats
00488   set->cluster_count = 0;
00489 
00490   for (i = 0; i < set->cluster_max_count; i++)
00491   {
00492     cluster = set->clusters + i;
00493     cluster->count = 0;
00494     cluster->weight = 0;
00495     cluster->mean = pf_vector_zero();
00496     cluster->cov = pf_matrix_zero();
00497 
00498     for (j = 0; j < 4; j++)
00499       cluster->m[j] = 0.0;
00500     for (j = 0; j < 2; j++)
00501       for (k = 0; k < 2; k++)
00502         cluster->c[j][k] = 0.0;
00503   }
00504 
00505   // Initialize overall filter stats
00506   count = 0;
00507   weight = 0.0;
00508   set->mean = pf_vector_zero();
00509   set->cov = pf_matrix_zero();
00510   for (j = 0; j < 4; j++)
00511     m[j] = 0.0;
00512   for (j = 0; j < 2; j++)
00513     for (k = 0; k < 2; k++)
00514       c[j][k] = 0.0;
00515   
00516   // Compute cluster stats
00517   for (i = 0; i < set->sample_count; i++)
00518   {
00519     sample = set->samples + i;
00520 
00521     //printf("%d %f %f %f\n", i, sample->pose.v[0], sample->pose.v[1], sample->pose.v[2]);
00522 
00523     // Get the cluster label for this sample
00524     cidx = pf_kdtree_get_cluster(set->kdtree, sample->pose);
00525     assert(cidx >= 0);
00526     if (cidx >= set->cluster_max_count)
00527       continue;
00528     if (cidx + 1 > set->cluster_count)
00529       set->cluster_count = cidx + 1;
00530     
00531     cluster = set->clusters + cidx;
00532 
00533     cluster->count += 1;
00534     cluster->weight += sample->weight;
00535 
00536     count += 1;
00537     weight += sample->weight;
00538 
00539     // Compute mean
00540     cluster->m[0] += sample->weight * sample->pose.v[0];
00541     cluster->m[1] += sample->weight * sample->pose.v[1];
00542     cluster->m[2] += sample->weight * cos(sample->pose.v[2]);
00543     cluster->m[3] += sample->weight * sin(sample->pose.v[2]);
00544 
00545     m[0] += sample->weight * sample->pose.v[0];
00546     m[1] += sample->weight * sample->pose.v[1];
00547     m[2] += sample->weight * cos(sample->pose.v[2]);
00548     m[3] += sample->weight * sin(sample->pose.v[2]);
00549 
00550     // Compute covariance in linear components
00551     for (j = 0; j < 2; j++)
00552       for (k = 0; k < 2; k++)
00553       {
00554         cluster->c[j][k] += sample->weight * sample->pose.v[j] * sample->pose.v[k];
00555         c[j][k] += sample->weight * sample->pose.v[j] * sample->pose.v[k];
00556       }
00557   }
00558 
00559   // Normalize
00560   for (i = 0; i < set->cluster_count; i++)
00561   {
00562     cluster = set->clusters + i;
00563         
00564     cluster->mean.v[0] = cluster->m[0] / cluster->weight;
00565     cluster->mean.v[1] = cluster->m[1] / cluster->weight;
00566     cluster->mean.v[2] = atan2(cluster->m[3], cluster->m[2]);
00567 
00568     cluster->cov = pf_matrix_zero();
00569 
00570     // Covariance in linear components
00571     for (j = 0; j < 2; j++)
00572       for (k = 0; k < 2; k++)
00573         cluster->cov.m[j][k] = cluster->c[j][k] / cluster->weight -
00574           cluster->mean.v[j] * cluster->mean.v[k];
00575 
00576     // Covariance in angular components; I think this is the correct
00577     // formula for circular statistics.
00578     cluster->cov.m[2][2] = -2 * log(sqrt(cluster->m[2] * cluster->m[2] +
00579                                          cluster->m[3] * cluster->m[3]));
00580 
00581     //printf("cluster %d %d %f (%f %f %f)\n", i, cluster->count, cluster->weight,
00582            //cluster->mean.v[0], cluster->mean.v[1], cluster->mean.v[2]);
00583     //pf_matrix_fprintf(cluster->cov, stdout, "%e");
00584   }
00585 
00586   // Compute overall filter stats
00587   set->mean.v[0] = m[0] / weight;
00588   set->mean.v[1] = m[1] / weight;
00589   set->mean.v[2] = atan2(m[3], m[2]);
00590 
00591   // Covariance in linear components
00592   for (j = 0; j < 2; j++)
00593     for (k = 0; k < 2; k++)
00594       set->cov.m[j][k] = c[j][k] / weight - set->mean.v[j] * set->mean.v[k];
00595 
00596   // Covariance in angular components; I think this is the correct
00597   // formula for circular statistics.
00598   set->cov.m[2][2] = -2 * log(sqrt(m[2] * m[2] + m[3] * m[3]));
00599 
00600   return;
00601 }
00602 
00603 
00604 // Compute the CEP statistics (mean and variance).
00605 void pf_get_cep_stats(pf_t *pf, pf_vector_t *mean, double *var)
00606 {
00607   int i;
00608   double mn, mx, my, mrr;
00609   pf_sample_set_t *set;
00610   pf_sample_t *sample;
00611   
00612   set = pf->sets + pf->current_set;
00613 
00614   mn = 0.0;
00615   mx = 0.0;
00616   my = 0.0;
00617   mrr = 0.0;
00618   
00619   for (i = 0; i < set->sample_count; i++)
00620   {
00621     sample = set->samples + i;
00622 
00623     mn += sample->weight;
00624     mx += sample->weight * sample->pose.v[0];
00625     my += sample->weight * sample->pose.v[1];
00626     mrr += sample->weight * sample->pose.v[0] * sample->pose.v[0];
00627     mrr += sample->weight * sample->pose.v[1] * sample->pose.v[1];
00628   }
00629 
00630   mean->v[0] = mx / mn;
00631   mean->v[1] = my / mn;
00632   mean->v[2] = 0.0;
00633 
00634   *var = mrr / mn - (mx * mx / (mn * mn) + my * my / (mn * mn));
00635 
00636   return;
00637 }
00638 
00639 
00640 // Get the statistics for a particular cluster.
00641 int pf_get_cluster_stats(pf_t *pf, int clabel, double *weight,
00642                          pf_vector_t *mean, pf_matrix_t *cov)
00643 {
00644   pf_sample_set_t *set;
00645   pf_cluster_t *cluster;
00646 
00647   set = pf->sets + pf->current_set;
00648 
00649   if (clabel >= set->cluster_count)
00650     return 0;
00651   cluster = set->clusters + clabel;
00652 
00653   *weight = cluster->weight;
00654   *mean = cluster->mean;
00655   *cov = cluster->cov;
00656 
00657   return 1;
00658 }
00659 
00660 


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:08