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


amcl
Author(s): Brian P. Gerkey, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:13