likelihood_field_model.hpp
Go to the documentation of this file.
1 // Copyright 2022-2023 Ekumen, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef BELUGA_SENSOR_LIKELIHOOD_FIELD_MODEL_HPP
16 #define BELUGA_SENSOR_LIKELIHOOD_FIELD_MODEL_HPP
17 
18 #include <algorithm>
19 #include <cmath>
20 #include <random>
21 #include <vector>
22 
26 #include <range/v3/range/conversion.hpp>
27 #include <range/v3/view/all.hpp>
28 #include <range/v3/view/transform.hpp>
29 #include <sophus/se2.hpp>
30 #include <sophus/so2.hpp>
31 
37 namespace beluga {
38 
40 
45 
49  double max_obstacle_distance = 100.0;
51  double max_laser_distance = 2.0;
53  double z_hit = 0.5;
55  double z_random = 0.5;
57 
60  double sigma_hit = 0.2;
61 };
62 
64 
77 template <class OccupancyGrid>
79  public:
83  using weight_type = double;
85  using measurement_type = std::vector<std::pair<double, double>>;
87  using map_type = OccupancyGrid;
90 
92 
99  explicit LikelihoodFieldModel(const param_type& params, const map_type& grid)
100  : params_{params},
102  world_to_likelihood_field_transform_{grid.origin().inverse()} {}
103 
105  [[nodiscard]] const auto& likelihood_field() const { return likelihood_field_; }
106 
108 
113  [[nodiscard]] auto operator()(measurement_type&& points) const {
114  return [this, points = std::move(points)](const state_type& state) -> weight_type {
115  const auto transform = world_to_likelihood_field_transform_ * state;
116  const auto x_offset = transform.translation().x();
117  const auto y_offset = transform.translation().y();
118  const auto cos_theta = transform.so2().unit_complex().x();
119  const auto sin_theta = transform.so2().unit_complex().y();
120  const auto unknown_space_occupancy_prob = 1. / params_.max_laser_distance;
121  // TODO(glpuga): Investigate why AMCL and QuickMCL both use this formula for the weight.
122  // See https://github.com/Ekumen-OS/beluga/issues/153
123  const auto unknown_space_occupancy_likelihood_cubed =
124  unknown_space_occupancy_prob * unknown_space_occupancy_prob * unknown_space_occupancy_prob;
125  return std::transform_reduce(
126  points.cbegin(), points.cend(), 1.0, std::plus{},
127  [this, x_offset, y_offset, cos_theta, sin_theta,
128  unknown_space_occupancy_likelihood_cubed](const auto& point) {
129  // Transform the end point of the laser to the grid local coordinate system.
130  // Not using Eigen/Sophus because they make the routine x10 slower.
131  // See `benchmark_likelihood_field_model.cpp` for reference.
132  const auto x = point.first * cos_theta - point.second * sin_theta + x_offset;
133  const auto y = point.first * sin_theta + point.second * cos_theta + y_offset;
134  // for performance, we store the likelihood already elevated to the cube
135  return likelihood_field_.data_near(x, y).value_or(unknown_space_occupancy_likelihood_cubed);
136  });
137  };
138  }
139 
141 
146  void update_map(const map_type& grid) {
148  world_to_likelihood_field_transform_ = grid.origin().inverse();
149  }
150 
151  private:
155 
156  static ValueGrid2<double> make_likelihood_field(const LikelihoodFieldModelParam& params, const OccupancyGrid& grid) {
157  const auto squared_distance = [&grid,
158  squared_max_distance = params.max_obstacle_distance * params.max_obstacle_distance](
159  std::size_t first, std::size_t second) {
160  return std::min((grid.coordinates_at(first) - grid.coordinates_at(second)).squaredNorm(), squared_max_distance);
161  };
162 
163  const auto neighborhood = [&grid](std::size_t index) { return grid.neighborhood4(index); };
164 
165  const auto distance_map = nearest_obstacle_distance_map(grid.obstacle_data(), squared_distance, neighborhood);
166 
167  const auto to_likelihood = [amplitude =
168  params.z_hit / (params.sigma_hit * std::sqrt(2 * Sophus::Constants<double>::pi())),
169  two_squared_sigma = 2 * params.sigma_hit * params.sigma_hit,
170  offset = params.z_random / params.max_laser_distance](double squared_distance) {
171  assert(two_squared_sigma > 0.0);
172  assert(amplitude > 0.0);
173  return amplitude * std::exp(-squared_distance / two_squared_sigma) + offset;
174  };
175 
176  // we store the likelihood elevated to the cube to save a few runtime computations
177  // when calculating the importance weight
178  const auto to_the_cube = [](auto likelihood) { return likelihood * likelihood * likelihood; };
179 
180  auto likelihood_data = distance_map | ranges::views::transform(to_likelihood) |
181  ranges::views::transform(to_the_cube) | ranges::to<std::vector>;
182  return ValueGrid2<double>{std::move(likelihood_data), grid.width(), grid.resolution()};
183  }
184 };
185 
186 } // namespace beluga
187 
188 #endif
beluga::LikelihoodFieldModelParam::max_laser_distance
double max_laser_distance
Maximum range of a laser ray.
Definition: likelihood_field_model.hpp:51
beluga::LikelihoodFieldModel::make_likelihood_field
static ValueGrid2< double > make_likelihood_field(const LikelihoodFieldModelParam &params, const OccupancyGrid &grid)
Definition: likelihood_field_model.hpp:156
beluga::LikelihoodFieldModelParam::sigma_hit
double sigma_hit
Standard deviation of a gaussian centered arounds obstacles.
Definition: likelihood_field_model.hpp:60
beluga::state
constexpr state_detail::state_fn state
Customization point object for accessing the state of a particle.
Definition: primitives.hpp:163
beluga::LikelihoodFieldModel::LikelihoodFieldModel
LikelihoodFieldModel(const param_type &params, const map_type &grid)
Constructs a LikelihoodFieldModel instance.
Definition: likelihood_field_model.hpp:99
beluga::LikelihoodFieldModel::measurement_type
std::vector< std::pair< double, double > > measurement_type
Measurement type of the sensor: a point cloud for the range finder.
Definition: likelihood_field_model.hpp:85
se2.hpp
beluga::LikelihoodFieldModelParam::max_obstacle_distance
double max_obstacle_distance
Maximum distance to obstacle.
Definition: likelihood_field_model.hpp:49
beluga::LikelihoodFieldModel
Likelihood field sensor model for range finders.
Definition: likelihood_field_model.hpp:78
value_grid.hpp
Implementation of generic value grid.
Sophus::SE2
beluga::LikelihoodFieldModel::params_
param_type params_
Definition: likelihood_field_model.hpp:152
beluga::LikelihoodFieldModel::likelihood_field_
ValueGrid2< double > likelihood_field_
Definition: likelihood_field_model.hpp:153
so2.hpp
occupancy_grid.hpp
Concepts and abstract implementations of occupancy grids.
beluga::ValueGrid2::width
std::size_t width() const
Gets grid width.
Definition: value_grid.hpp:50
beluga::LikelihoodFieldModelParam
Parameters used to construct a LikelihoodFieldModel instance.
Definition: likelihood_field_model.hpp:43
beluga::LikelihoodFieldModel::world_to_likelihood_field_transform_
Sophus::SE2d world_to_likelihood_field_transform_
Definition: likelihood_field_model.hpp:154
beluga::nearest_obstacle_distance_map
auto nearest_obstacle_distance_map(Range &&obstacle_map, DistanceFunction &&distance_function, NeighborsFunction &&neighbors_function)
Returns a map where the value of each cell is the distance to the nearest obstacle.
Definition: distance_map.hpp:54
beluga::LikelihoodFieldModel::weight_type
double weight_type
Weight type of the particle.
Definition: likelihood_field_model.hpp:83
beluga::LikelihoodFieldModel::map_type
OccupancyGrid map_type
Map representation type.
Definition: likelihood_field_model.hpp:87
beluga::LikelihoodFieldModel::likelihood_field
const auto & likelihood_field() const
Returns the likelihood field, constructed from the provided map.
Definition: likelihood_field_model.hpp:105
Sophus::Constants
beluga::LikelihoodFieldModelParam::z_random
double z_random
Weight used to combine the probability of random noise in perception.
Definition: likelihood_field_model.hpp:55
distance_map.hpp
Implementation of algorithm to calculate distance from obstacles.
beluga::LikelihoodFieldModelParam::z_hit
double z_hit
Weight used to combine the probability of hitting an obstacle.
Definition: likelihood_field_model.hpp:53
Sophus::SE2d
SE2< double > SE2d
beluga::LikelihoodFieldModel::operator()
auto operator()(measurement_type &&points) const
Returns a state weighting function conditioned on 2D lidar hits.
Definition: likelihood_field_model.hpp:113
beluga::ValueGrid2< double >
beluga::LikelihoodFieldModel::update_map
void update_map(const map_type &grid)
Update the sensor model with a new occupancy grid map.
Definition: likelihood_field_model.hpp:146
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53