Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
likelihood_field_model.cpp
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 #include <cassert>
23 #include <cmath>
24 
25 #include "nav2_amcl/sensors/laser/laser.hpp"
26 
27 namespace nav2_amcl
28 {
29 
30 LikelihoodFieldModel::LikelihoodFieldModel(
31  double z_hit, double z_rand, double sigma_hit,
32  double max_occ_dist, size_t max_beams, map_t * map)
33 : Laser(max_beams, map)
34 {
35  z_hit_ = z_hit;
36  z_rand_ = z_rand;
37  sigma_hit_ = sigma_hit;
38 
39  // recompute cspace only when necessary, i.e. if:
40  // - max_occ_dist changed
41  // OR
42  // - cspace was not computed yet, i.e. when map->max_occ_dist == 0.0 (and hence different from
43  // max_occ_dist)
44  if (map->max_occ_dist != max_occ_dist) {
45  map_update_cspace(map, max_occ_dist);
46  }
47 }
48 
49 double
50 LikelihoodFieldModel::sensorFunction(LaserData * data, pf_sample_set_t * set)
51 {
52  LikelihoodFieldModel * self;
53  int i, j, step;
54  double z, pz;
55  double p;
56  double obs_range, obs_bearing;
57  double total_weight;
58  pf_sample_t * sample;
59  pf_vector_t pose;
60  pf_vector_t hit;
61 
62  self = reinterpret_cast<LikelihoodFieldModel *>(data->laser);
63 
64  // Pre-compute a couple of things
65  double z_hit_denom = 2 * self->sigma_hit_ * self->sigma_hit_;
66  double z_rand_mult = 1.0 / data->range_max;
67 
68  step = (data->range_count - 1) / (self->max_beams_ - 1);
69 
70  // Step size must be at least 1
71  if (step < 1) {
72  step = 1;
73  }
74 
75  total_weight = 0.0;
76 
77  // Compute the sample weights
78  for (j = 0; j < set->sample_count; j++) {
79  sample = set->samples + j;
80  pose = sample->pose;
81 
82  // Take account of the laser pose relative to the robot
83  pose = pf_vector_coord_add(self->laser_pose_, pose);
84 
85  p = 1.0;
86 
87  for (i = 0; i < data->range_count; i += step) {
88  obs_range = data->ranges[i][0];
89  obs_bearing = data->ranges[i][1];
90 
91  // This model ignores max range readings
92  if (obs_range >= data->range_max) {
93  continue;
94  }
95 
96  // Check for NaN
97  if (obs_range != obs_range) {
98  continue;
99  }
100 
101  pz = 0.0;
102 
103  // Compute the endpoint of the beam
104  hit.v[0] = pose.v[0] + obs_range * cos(pose.v[2] + obs_bearing);
105  hit.v[1] = pose.v[1] + obs_range * sin(pose.v[2] + obs_bearing);
106 
107  // Convert to map grid coords.
108  int mi, mj;
109  mi = MAP_GXWX(self->map_, hit.v[0]);
110  mj = MAP_GYWY(self->map_, hit.v[1]);
111 
112  // Part 1: Get distance from the hit to closest obstacle.
113  // Off-map penalized as max distance
114  if (!MAP_VALID(self->map_, mi, mj)) {
115  z = self->map_->max_occ_dist;
116  } else {
117  z = self->map_->cells[MAP_INDEX(self->map_, mi, mj)].occ_dist;
118  }
119  // Gaussian model
120  // NOTE: this should have a normalization of 1/(sqrt(2pi)*sigma)
121  pz += self->z_hit_ * exp(-(z * z) / z_hit_denom);
122  // Part 2: random measurements
123  pz += self->z_rand_ * z_rand_mult;
124 
125  // TODO(?): outlier rejection for short readings
126 
127  assert(pz <= 1.0);
128  assert(pz >= 0.0);
129  // p *= pz;
130  // here we have an ad-hoc weighting scheme for combining beam probs
131  // works well, though...
132  p += pz * pz * pz;
133  }
134 
135  sample->weight *= p;
136  total_weight += sample->weight;
137  }
138 
139  return total_weight;
140 }
141 
142 
143 bool
144 LikelihoodFieldModel::sensorUpdate(pf_t * pf, LaserData * data)
145 {
146  if (max_beams_ < 2) {
147  return false;
148  }
149  pf_update_sensor(pf, (pf_sensor_model_fn_t) sensorFunction, data);
150 
151  return true;
152 }
153 
154 } // namespace nav2_amcl
Definition: pf.hpp:112
Definition: map.hpp:62