amcl_laser.cpp
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  */
22 //
23 // Desc: AMCL laser routines
24 // Author: Andrew Howard
25 // Date: 6 Feb 2003
26 // CVS: $Id: amcl_laser.cc 7057 2008-10-02 00:44:06Z gbiggs $
27 //
29 
30 #include <sys/types.h> // required by Darwin
31 #include <math.h>
32 #include <stdlib.h>
33 #include <assert.h>
34 #include <unistd.h>
35 
37 
38 using namespace amcl;
39 
41 // Default constructor
42 AMCLLaser::AMCLLaser(size_t max_beams, map_t* map) : AMCLSensor(),
43  max_samples(0), max_obs(0),
44  temp_obs(NULL)
45 {
46  this->time = 0.0;
47 
48  this->max_beams = max_beams;
49  this->map = map;
50 
51  return;
52 }
53 
55 {
56  if(temp_obs){
57  for(int k=0; k < max_samples; k++){
58  delete [] temp_obs[k];
59  }
60  delete []temp_obs;
61  }
62 }
63 
64 void
66  double z_short,
67  double z_max,
68  double z_rand,
69  double sigma_hit,
70  double lambda_short,
71  double chi_outlier)
72 {
74  this->z_hit = z_hit;
75  this->z_short = z_short;
76  this->z_max = z_max;
77  this->z_rand = z_rand;
78  this->sigma_hit = sigma_hit;
79  this->lambda_short = lambda_short;
80  this->chi_outlier = chi_outlier;
81 }
82 
83 void
85  double z_rand,
86  double sigma_hit,
87  double max_occ_dist)
88 {
90  this->z_hit = z_hit;
91  this->z_rand = z_rand;
92  this->sigma_hit = sigma_hit;
93 
94  map_update_cspace(this->map, max_occ_dist);
95 }
96 
97 void
99  double z_rand,
100  double sigma_hit,
101  double max_occ_dist,
102  bool do_beamskip,
103  double beam_skip_distance,
104  double beam_skip_threshold,
106 {
108  this->z_hit = z_hit;
109  this->z_rand = z_rand;
110  this->sigma_hit = sigma_hit;
111  this->do_beamskip = do_beamskip;
112  this->beam_skip_distance = beam_skip_distance;
113  this->beam_skip_threshold = beam_skip_threshold;
114  this->beam_skip_error_threshold = beam_skip_error_threshold;
115  map_update_cspace(this->map, max_occ_dist);
116 }
117 
118 
120 // Apply the laser sensor model
122 {
123  if (this->max_beams < 2)
124  return false;
125 
126  // Apply the laser sensor model
127  if(this->model_type == LASER_MODEL_BEAM)
129  else if(this->model_type == LASER_MODEL_LIKELIHOOD_FIELD)
133  else
134  pf_update_sensor(pf, (pf_sensor_model_fn_t) BeamModel, data);
135 
136  return true;
137 }
138 
139 
141 // Determine the probability for the given pose
143 {
144  AMCLLaser *self;
145  int i, j, step;
146  double z, pz;
147  double p;
148  double map_range;
149  double obs_range, obs_bearing;
150  double total_weight;
151  pf_sample_t *sample;
153 
154  self = (AMCLLaser*) data->sensor;
155 
156  total_weight = 0.0;
157 
158  // Compute the sample weights
159  for (j = 0; j < set->sample_count; j++)
160  {
161  sample = set->samples + j;
162  pose = sample->pose;
163 
164  // Take account of the laser pose relative to the robot
165  pose = pf_vector_coord_add(self->laser_pose, pose);
166 
167  p = 1.0;
168 
169  step = (data->range_count - 1) / (self->max_beams - 1);
170  for (i = 0; i < data->range_count; i += step)
171  {
172  obs_range = data->ranges[i][0];
173  obs_bearing = data->ranges[i][1];
174 
175  // Compute the range according to the map
176  map_range = map_calc_range(self->map, pose.v[0], pose.v[1],
177  pose.v[2] + obs_bearing, data->range_max);
178  pz = 0.0;
179 
180  // Part 1: good, but noisy, hit
181  z = obs_range - map_range;
182  pz += self->z_hit * exp(-(z * z) / (2 * self->sigma_hit * self->sigma_hit));
183 
184  // Part 2: short reading from unexpected obstacle (e.g., a person)
185  if(z < 0)
186  pz += self->z_short * self->lambda_short * exp(-self->lambda_short*obs_range);
187 
188  // Part 3: Failure to detect obstacle, reported as max-range
189  if(obs_range == data->range_max)
190  pz += self->z_max * 1.0;
191 
192  // Part 4: Random measurements
193  if(obs_range < data->range_max)
194  pz += self->z_rand * 1.0/data->range_max;
195 
196  // TODO: outlier rejection for short readings
197 
198  assert(pz <= 1.0);
199  assert(pz >= 0.0);
200  // p *= pz;
201  // here we have an ad-hoc weighting scheme for combining beam probs
202  // works well, though...
203  p += pz*pz*pz;
204  }
205 
206  sample->weight *= p;
207  total_weight += sample->weight;
208  }
209 
210  return(total_weight);
211 }
212 
214 {
215  AMCLLaser *self;
216  int i, j, step;
217  double z, pz;
218  double p;
219  double obs_range, obs_bearing;
220  double total_weight;
221  pf_sample_t *sample;
223  pf_vector_t hit;
224 
225  self = (AMCLLaser*) data->sensor;
226 
227  total_weight = 0.0;
228 
229  // Compute the sample weights
230  for (j = 0; j < set->sample_count; j++)
231  {
232  sample = set->samples + j;
233  pose = sample->pose;
234 
235  // Take account of the laser pose relative to the robot
236  pose = pf_vector_coord_add(self->laser_pose, pose);
237 
238  p = 1.0;
239 
240  // Pre-compute a couple of things
241  double z_hit_denom = 2 * self->sigma_hit * self->sigma_hit;
242  double z_rand_mult = 1.0/data->range_max;
243 
244  step = (data->range_count - 1) / (self->max_beams - 1);
245 
246  // Step size must be at least 1
247  if(step < 1)
248  step = 1;
249 
250  for (i = 0; i < data->range_count; i += step)
251  {
252  obs_range = data->ranges[i][0];
253  obs_bearing = data->ranges[i][1];
254 
255  // This model ignores max range readings
256  if(obs_range >= data->range_max)
257  continue;
258 
259  // Check for NaN
260  if(obs_range != obs_range)
261  continue;
262 
263  pz = 0.0;
264 
265  // Compute the endpoint of the beam
266  hit.v[0] = pose.v[0] + obs_range * cos(pose.v[2] + obs_bearing);
267  hit.v[1] = pose.v[1] + obs_range * sin(pose.v[2] + obs_bearing);
268 
269  // Convert to map grid coords.
270  int mi, mj;
271  mi = MAP_GXWX(self->map, hit.v[0]);
272  mj = MAP_GYWY(self->map, hit.v[1]);
273 
274  // Part 1: Get distance from the hit to closest obstacle.
275  // Off-map penalized as max distance
276  if(!MAP_VALID(self->map, mi, mj))
277  z = self->map->max_occ_dist;
278  else
279  z = self->map->cells[MAP_INDEX(self->map,mi,mj)].occ_dist;
280  // Gaussian model
281  // NOTE: this should have a normalization of 1/(sqrt(2pi)*sigma)
282  pz += self->z_hit * exp(-(z * z) / z_hit_denom);
283  // Part 2: random measurements
284  pz += self->z_rand * z_rand_mult;
285 
286  // TODO: outlier rejection for short readings
287 
288  assert(pz <= 1.0);
289  assert(pz >= 0.0);
290  // p *= pz;
291  // here we have an ad-hoc weighting scheme for combining beam probs
292  // works well, though...
293  p += pz*pz*pz;
294  }
295 
296  sample->weight *= p;
297  total_weight += sample->weight;
298  }
299 
300  return(total_weight);
301 }
302 
304 {
305  AMCLLaser *self;
306  int i, j, step;
307  double z, pz;
308  double log_p;
309  double obs_range, obs_bearing;
310  double total_weight;
311  pf_sample_t *sample;
313  pf_vector_t hit;
314 
315  self = (AMCLLaser*) data->sensor;
316 
317  total_weight = 0.0;
318 
319  step = ceil((data->range_count) / static_cast<double>(self->max_beams));
320 
321  // Step size must be at least 1
322  if(step < 1)
323  step = 1;
324 
325  // Pre-compute a couple of things
326  double z_hit_denom = 2 * self->sigma_hit * self->sigma_hit;
327  double z_rand_mult = 1.0/data->range_max;
328 
329  double max_dist_prob = exp(-(self->map->max_occ_dist * self->map->max_occ_dist) / z_hit_denom);
330 
331  //Beam skipping - ignores beams for which a majoirty of particles do not agree with the map
332  //prevents correct particles from getting down weighted because of unexpected obstacles
333  //such as humans
334 
335  bool do_beamskip = self->do_beamskip;
336  double beam_skip_distance = self->beam_skip_distance;
337  double beam_skip_threshold = self->beam_skip_threshold;
338 
339  //we only do beam skipping if the filter has converged
340  if(do_beamskip && !set->converged){
341  do_beamskip = false;
342  }
343 
344  //we need a count the no of particles for which the beam agreed with the map
345  int *obs_count = new int[self->max_beams]();
346 
347  //we also need a mask of which observations to integrate (to decide which beams to integrate to all particles)
348  bool *obs_mask = new bool[self->max_beams]();
349 
350  int beam_ind = 0;
351 
352  //realloc indicates if we need to reallocate the temp data structure needed to do beamskipping
353  bool realloc = false;
354 
355  if(do_beamskip){
356  if(self->max_obs < self->max_beams){
357  realloc = true;
358  }
359 
360  if(self->max_samples < set->sample_count){
361  realloc = true;
362  }
363 
364  if(realloc){
365  self->reallocTempData(set->sample_count, self->max_beams);
366  fprintf(stderr, "Reallocing temp weights %d - %d\n", self->max_samples, self->max_obs);
367  }
368  }
369 
370  // Compute the sample weights
371  for (j = 0; j < set->sample_count; j++)
372  {
373  sample = set->samples + j;
374  pose = sample->pose;
375 
376  // Take account of the laser pose relative to the robot
377  pose = pf_vector_coord_add(self->laser_pose, pose);
378 
379  log_p = 0;
380 
381  beam_ind = 0;
382 
383  for (i = 0; i < data->range_count; i += step, beam_ind++)
384  {
385  obs_range = data->ranges[i][0];
386  obs_bearing = data->ranges[i][1];
387 
388  // This model ignores max range readings
389  if(obs_range >= data->range_max){
390  continue;
391  }
392 
393  // Check for NaN
394  if(obs_range != obs_range){
395  continue;
396  }
397 
398  pz = 0.0;
399 
400  // Compute the endpoint of the beam
401  hit.v[0] = pose.v[0] + obs_range * cos(pose.v[2] + obs_bearing);
402  hit.v[1] = pose.v[1] + obs_range * sin(pose.v[2] + obs_bearing);
403 
404  // Convert to map grid coords.
405  int mi, mj;
406  mi = MAP_GXWX(self->map, hit.v[0]);
407  mj = MAP_GYWY(self->map, hit.v[1]);
408 
409  // Part 1: Get distance from the hit to closest obstacle.
410  // Off-map penalized as max distance
411 
412  if(!MAP_VALID(self->map, mi, mj)){
413  pz += self->z_hit * max_dist_prob;
414  }
415  else{
416  z = self->map->cells[MAP_INDEX(self->map,mi,mj)].occ_dist;
417  if(z < beam_skip_distance){
418  obs_count[beam_ind] += 1;
419  }
420  pz += self->z_hit * exp(-(z * z) / z_hit_denom);
421  }
422 
423  // Gaussian model
424  // NOTE: this should have a normalization of 1/(sqrt(2pi)*sigma)
425 
426  // Part 2: random measurements
427  pz += self->z_rand * z_rand_mult;
428 
429  assert(pz <= 1.0);
430  assert(pz >= 0.0);
431 
432  // TODO: outlier rejection for short readings
433 
434  if(!do_beamskip){
435  log_p += log(pz);
436  }
437  else{
438  self->temp_obs[j][beam_ind] = pz;
439  }
440  }
441  if(!do_beamskip){
442  sample->weight *= exp(log_p);
443  total_weight += sample->weight;
444  }
445  }
446 
447  if(do_beamskip){
448  int skipped_beam_count = 0;
449  for (beam_ind = 0; beam_ind < self->max_beams; beam_ind++){
450  if((obs_count[beam_ind] / static_cast<double>(set->sample_count)) > beam_skip_threshold){
451  obs_mask[beam_ind] = true;
452  }
453  else{
454  obs_mask[beam_ind] = false;
455  skipped_beam_count++;
456  }
457  }
458 
459  //we check if there is at least a critical number of beams that agreed with the map
460  //otherwise it probably indicates that the filter converged to a wrong solution
461  //if that's the case we integrate all the beams and hope the filter might converge to
462  //the right solution
463  bool error = false;
464 
465  if(skipped_beam_count >= (beam_ind * self->beam_skip_error_threshold)){
466  fprintf(stderr, "Over %f%% of the observations were not in the map - pf may have converged to wrong pose - integrating all observations\n", (100 * self->beam_skip_error_threshold));
467  error = true;
468  }
469 
470  for (j = 0; j < set->sample_count; j++)
471  {
472  sample = set->samples + j;
473  pose = sample->pose;
474 
475  log_p = 0;
476 
477  for (beam_ind = 0; beam_ind < self->max_beams; beam_ind++){
478  if(error || obs_mask[beam_ind]){
479  log_p += log(self->temp_obs[j][beam_ind]);
480  }
481  }
482 
483  sample->weight *= exp(log_p);
484 
485  total_weight += sample->weight;
486  }
487  }
488 
489  delete [] obs_count;
490  delete [] obs_mask;
491  return(total_weight);
492 }
493 
494 void AMCLLaser::reallocTempData(int new_max_samples, int new_max_obs){
495  if(temp_obs){
496  for(int k=0; k < max_samples; k++){
497  delete [] temp_obs[k];
498  }
499  delete []temp_obs;
500  }
501  max_obs = new_max_obs;
502  max_samples = fmax(max_samples, new_max_samples);
503 
504  temp_obs = new double*[max_samples]();
505  for(int k=0; k < max_samples; k++){
506  temp_obs[k] = new double[max_obs]();
507  }
508 }
#define MAP_GXWX(map, x)
Definition: map.h:137
double beam_skip_distance
Definition: amcl_laser.h:126
double(* pf_sensor_model_fn_t)(void *sensor_data, struct _pf_sample_set_t *set)
Definition: pf.h:54
void map_update_cspace(map_t *map, double max_occ_dist)
Definition: map_cspace.cpp:120
laser_model_t model_type
Definition: amcl_laser.h:110
double v[3]
Definition: pf_vector.h:40
void pf_update_sensor(pf_t *pf, pf_sensor_model_fn_t sensor_fn, void *sensor_data)
Definition: pf.c:267
Definition: pf.h:112
#define MAP_VALID(map, i, j)
Definition: map.h:141
double sigma_hit
Definition: amcl_laser.h:146
#define MAP_INDEX(map, i, j)
Definition: map.h:144
#define MAP_GYWY(map, y)
Definition: map.h:138
void SetModelBeam(double z_hit, double z_short, double z_max, double z_rand, double sigma_hit, double labda_short, double chi_outlier)
Definition: amcl_laser.cpp:65
double map_calc_range(map_t *map, double ox, double oy, double oa, double max_range)
Definition: map_range.c:38
void reallocTempData(int max_samples, int max_obs)
Definition: amcl_laser.cpp:494
double beam_skip_error_threshold
Definition: amcl_laser.h:130
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
double chi_outlier
Definition: amcl_laser.h:150
pf_vector_t pose
Definition: amcl_sensor.h:65
virtual bool UpdateSensor(pf_t *pf, AMCLSensorData *data)
Definition: amcl_laser.cpp:121
Definition: map.h:61
AMCLSensor * sensor
Definition: amcl_sensor.h:88
Definition: pf.h:59
static double LikelihoodFieldModelProb(AMCLLaserData *data, pf_sample_set_t *set)
Definition: amcl_laser.cpp:303
double(* ranges)[2]
Definition: amcl_laser.h:54
virtual ~AMCLLaser()
Definition: amcl_laser.cpp:54
void SetModelLikelihoodField(double z_hit, double z_rand, double sigma_hit, double max_occ_dist)
Definition: amcl_laser.cpp:84
pf_vector_t pf_vector_coord_add(pf_vector_t a, pf_vector_t b)
Definition: pf_vector.c:106
static double LikelihoodFieldModel(AMCLLaserData *data, pf_sample_set_t *set)
Definition: amcl_laser.cpp:213
TFSIMD_FORCE_INLINE const tfScalar & z() const
unsigned int step
pf_vector_t pose
Definition: pf.h:62
double lambda_short
Definition: amcl_laser.h:148
static double BeamModel(AMCLLaserData *data, pf_sample_set_t *set)
Definition: amcl_laser.cpp:142
double weight
Definition: pf.h:65
double ** temp_obs
Definition: amcl_laser.h:135
AMCLLaser(size_t max_beams, map_t *map)
Definition: amcl_laser.cpp:42
double beam_skip_threshold
Definition: amcl_laser.h:127
void SetModelLikelihoodFieldProb(double z_hit, double z_rand, double sigma_hit, double max_occ_dist, bool do_beamskip, double beam_skip_distance, double beam_skip_threshold, double beam_skip_error_threshold)
Definition: amcl_laser.cpp:98


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:36