beam_model.hpp
Go to the documentation of this file.
1 // Copyright 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_BEAM_MODEL_HPP
16 #define BELUGA_SENSOR_BEAM_MODEL_HPP
17 
18 #include <algorithm>
19 #include <cmath>
20 #include <random>
21 #include <vector>
22 
24 
25 #include <range/v3/range/conversion.hpp>
26 #include <range/v3/view/all.hpp>
27 #include <range/v3/view/transform.hpp>
28 #include <sophus/se2.hpp>
29 #include <sophus/so2.hpp>
30 
36 namespace beluga {
37 
39 
44  double z_hit{0.5};
46  double z_short{0.5};
48  double z_max{0.05};
50  double z_rand{0.05};
52  double sigma_hit{0.2};
54  double lambda_short{0.1};
56  double beam_max_range{60};
57 };
58 
60 
74 template <class OccupancyGrid>
76  public:
80  using weight_type = double;
82  using measurement_type = std::vector<std::pair<double, double>>;
84  using map_type = OccupancyGrid;
87 
89 
95  explicit BeamSensorModel(const param_type& params, OccupancyGrid grid) : params_{params}, grid_{std::move(grid)} {}
96 
98 
103  [[nodiscard]] auto operator()(measurement_type&& points) const {
104  return [this, points = std::move(points)](const state_type& state) -> weight_type {
105  const auto beam = Ray2d{grid_, state, params_.beam_max_range};
106  const double n = 1. / (std::sqrt(2. * M_PI) * params_.sigma_hit);
107  return std::transform_reduce(
108  points.cbegin(), points.cend(), 0.0, std::plus{}, [this, &beam, n](const auto& point) {
109  // TODO(Ramiro): We're converting from range + bearing to cartesian points in the ROS node, but we want
110  // range
111  // + bearing here. We might want to make that conversion in the likelihood model instead, and let the
112  // measurement type be range, bearing instead of x, y.
113 
114  // Compute the range according to the measurement.
115  const double z = std::sqrt(point.first * point.first + point.second * point.second);
116 
117  // dirty hack to prevent SO2d from calculating the hypot again to normalize the vector.
118  auto beam_bearing = Sophus::SO2d{};
119  beam_bearing.data()[0] = point.first / z;
120  beam_bearing.data()[1] = point.second / z;
121 
122  // Compute range according to the map (raycasting).
123  const double z_mean = beam.cast(beam_bearing).value_or(params_.beam_max_range);
124  // 1: Correct range with local measurement noise.
125  const double eta_hit =
126  2. / (std::erf((params_.beam_max_range - z_mean) / (std::sqrt(2.) * params_.sigma_hit)) -
127  std::erf(-z_mean / (std::sqrt(2.) * params_.sigma_hit)));
128  const double d = (z - z_mean) / params_.sigma_hit;
129  double pz = params_.z_hit * eta_hit * n * std::exp(-(d * d) / 2.);
130 
131  // 2: Unexpected objects.
132  if (z < z_mean) {
133  const double eta_short = 1. / (1. - std::exp(-params_.lambda_short * z_mean));
134  pz += params_.z_short * params_.lambda_short * eta_short * std::exp(-params_.lambda_short * z);
135  }
136 
137  // 3 and 4: Max range return or random return.
138  if (z < params_.beam_max_range) {
140  } else {
141  pz += params_.z_max;
142  }
143 
144  // TODO(glpuga): Investigate why AMCL and QuickMCL both use this formula for the weight.
145  // See https://github.com/Ekumen-OS/beluga/issues/153
146  return pz * pz * pz;
147  });
148  };
149  }
150 
152 
155  void update_map(map_type&& map) { grid_ = std::move(map); }
156 
157  private:
159  OccupancyGrid grid_;
160 };
161 
162 } // namespace beluga
163 
164 #endif
beluga::BeamModelParam::z_rand
double z_rand
Weight associated with random readings.
Definition: beam_model.hpp:50
beluga::BeamModelParam::lambda_short
double lambda_short
Intrinsic parameter assoaciated with short readings distribution.
Definition: beam_model.hpp:54
raycasting.hpp
Implementation of raycasting algorithms.
beluga::BeamSensorModel::map_type
OccupancyGrid map_type
Map representation type.
Definition: beam_model.hpp:84
beluga::state
constexpr state_detail::state_fn state
Customization point object for accessing the state of a particle.
Definition: primitives.hpp:163
beluga::BeamSensorModel::params_
param_type params_
Definition: beam_model.hpp:158
beluga::BeamModelParam::z_hit
double z_hit
Weight associated with good but noisy readings.
Definition: beam_model.hpp:44
se2.hpp
beluga::BeamSensorModel::update_map
void update_map(map_type &&map)
Update the sensor model with a new occupancy grid map.
Definition: beam_model.hpp:155
beluga::BeamSensorModel::operator()
auto operator()(measurement_type &&points) const
Returns a state weighting function conditioned on 2D lidar hits.
Definition: beam_model.hpp:103
beluga::BeamModelParam::beam_max_range
double beam_max_range
Maximum beam range. This is the expected value in case of a miss.
Definition: beam_model.hpp:56
Sophus::SE2
beluga::BeamSensorModel::BeamSensorModel
BeamSensorModel(const param_type &params, OccupancyGrid grid)
Constructs a BeamSensorModel instance.
Definition: beam_model.hpp:95
beluga::BeamSensorModel::weight_type
double weight_type
Weight type of the particle.
Definition: beam_model.hpp:80
so2.hpp
beluga::BeamModelParam::z_short
double z_short
Weight associated with unexpected obstacles.
Definition: beam_model.hpp:46
beluga::BeamModelParam::z_max
double z_max
Weight associated with max range readings.
Definition: beam_model.hpp:48
beluga::BeamSensorModel::measurement_type
std::vector< std::pair< double, double > > measurement_type
Measurement type of the sensor: a point cloud for the range finder.
Definition: beam_model.hpp:82
beluga::BeamModelParam::sigma_hit
double sigma_hit
Standard deviation of the gaussian noise associated with hits.
Definition: beam_model.hpp:52
beluga::BeamSensorModel
Beam sensor model for range finders.
Definition: beam_model.hpp:75
Sophus::SE2d
SE2< double > SE2d
beluga::BeamSensorModel::grid_
OccupancyGrid grid_
Definition: beam_model.hpp:159
beluga::BeamModelParam
Parameters used to construct a BeamSensorModel instance.
Definition: beam_model.hpp:42
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21
beluga::Ray2d
Castable 2D ray.
Definition: include/beluga/algorithm/raycasting.hpp:44


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