Template Class LikelihoodFieldModel
Defined in File likelihood_field_model.hpp
Class Documentation
-
template<class OccupancyGrid>
class LikelihoodFieldModel Likelihood field sensor model for range finders.
This model relies on a pre-computed likelihood map of the environment. It is less computationally intensive than the beluga::BeamSensorModel because no ray-tracing is required, and it can also provide better performance in environments with non-smooth occupation maps. See Probabilistic Robotics thrun2005probabilistic, Chapter 6.4, for further reference.
Note
This class satisfies Beluga named requirements: SensorModel.
- Template Parameters:
OccupancyGrid – Type representing an occupancy grid. It must satisfy Beluga named requirements: OccupancyGrid2d.
Public Types
-
using state_type = Sophus::SE2d
State type of a particle.
-
using weight_type = double
Weight type of the particle.
-
using measurement_type = std::vector<std::pair<double, double>>
Measurement type of the sensor: a point cloud for the range finder.
-
using map_type = OccupancyGrid
Map representation type.
-
using param_type = LikelihoodFieldModelParam
Parameter type that the constructor uses to configure the likelihood field model.
Public Functions
-
inline explicit LikelihoodFieldModel(const param_type ¶ms, const map_type &grid)
Constructs a LikelihoodFieldModel instance.
- Parameters:
params – Parameters to configure this instance. See beluga::LikelihoodFieldModelParam for details.
grid – Occupancy grid representing the static map that the sensor model uses to compute a likelihood field for lidar hits and compute importance weights for particle states.
-
inline const auto &likelihood_field() const
Returns the likelihood field, constructed from the provided map.
-
inline auto operator()(measurement_type &&points) const
Returns a state weighting function conditioned on 2D lidar hits.
- Parameters:
points – 2D lidar hit points in the reference frame of particle states.
- Returns:
a state weighting function satisfying Beluga named requirements: StateWeightingFunction and borrowing a reference to this sensor model (and thus their lifetime are bound).