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