Likelihood field sensor model for range finders. More...
#include <likelihood_field_model.hpp>
Public Types | |
using | map_type = OccupancyGrid |
Map representation type. More... | |
using | measurement_type = std::vector< std::pair< double, double > > |
Measurement type of the sensor: a point cloud for the range finder. More... | |
using | param_type = LikelihoodFieldModelParam |
Parameter type that the constructor uses to configure the likelihood field model. More... | |
using | state_type = Sophus::SE2d |
State type of a particle. More... | |
using | weight_type = double |
Weight type of the particle. More... | |
Public Member Functions | |
const auto & | likelihood_field () const |
Returns the likelihood field, constructed from the provided map. More... | |
LikelihoodFieldModel (const param_type ¶ms, const map_type &grid) | |
Constructs a LikelihoodFieldModel instance. More... | |
auto | operator() (measurement_type &&points) const |
Returns a state weighting function conditioned on 2D lidar hits. More... | |
void | update_map (const map_type &grid) |
Update the sensor model with a new occupancy grid map. More... | |
Static Private Member Functions | |
static ValueGrid2< double > | make_likelihood_field (const LikelihoodFieldModelParam ¶ms, const OccupancyGrid &grid) |
Private Attributes | |
ValueGrid2< double > | likelihood_field_ |
param_type | params_ |
Sophus::SE2d | world_to_likelihood_field_transform_ |
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.
OccupancyGrid | Type representing an occupancy grid. It must satisfy Beluga named requirements: OccupancyGrid2d. |
Definition at line 78 of file likelihood_field_model.hpp.
using beluga::LikelihoodFieldModel< OccupancyGrid >::map_type = OccupancyGrid |
Map representation type.
Definition at line 87 of file likelihood_field_model.hpp.
using beluga::LikelihoodFieldModel< OccupancyGrid >::measurement_type = std::vector<std::pair<double, double> > |
Measurement type of the sensor: a point cloud for the range finder.
Definition at line 85 of file likelihood_field_model.hpp.
using beluga::LikelihoodFieldModel< OccupancyGrid >::param_type = LikelihoodFieldModelParam |
Parameter type that the constructor uses to configure the likelihood field model.
Definition at line 89 of file likelihood_field_model.hpp.
using beluga::LikelihoodFieldModel< OccupancyGrid >::state_type = Sophus::SE2d |
State type of a particle.
Definition at line 81 of file likelihood_field_model.hpp.
using beluga::LikelihoodFieldModel< OccupancyGrid >::weight_type = double |
Weight type of the particle.
Definition at line 83 of file likelihood_field_model.hpp.
|
inlineexplicit |
Constructs a LikelihoodFieldModel instance.
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. |
Definition at line 99 of file likelihood_field_model.hpp.
|
inline |
Returns the likelihood field, constructed from the provided map.
Definition at line 105 of file likelihood_field_model.hpp.
|
inlinestaticprivate |
Definition at line 156 of file likelihood_field_model.hpp.
|
inline |
Returns a state weighting function conditioned on 2D lidar hits.
points | 2D lidar hit points in the reference frame of particle states. |
Definition at line 113 of file likelihood_field_model.hpp.
|
inline |
Update the sensor model with a new occupancy grid map.
This method re-computes the underlying likelihood field.
grid | New occupancy grid representing the static map. |
Definition at line 146 of file likelihood_field_model.hpp.
|
private |
Definition at line 153 of file likelihood_field_model.hpp.
|
private |
Definition at line 152 of file likelihood_field_model.hpp.
|
private |
Definition at line 154 of file likelihood_field_model.hpp.