Template Class LikelihoodFieldModelBase

Inheritance Relationships

Derived Types

Class Documentation

template<class OccupancyGrid>
class LikelihoodFieldModelBase

Likelihood field common 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.

Subclassed by beluga::LikelihoodFieldModel< OccupancyGrid >, beluga::LikelihoodFieldProbModel< OccupancyGrid >

Public Types

using map_type = OccupancyGrid

Map representation type.

using param_type = LikelihoodFieldModelBaseParam

Parameter type that the constructor uses to configure the likelihood field model.

Public Functions

inline explicit LikelihoodFieldModelBase(const param_type &params, const map_type &grid)

Constructs a LikelihoodFieldCommonModel instance.

Parameters:
  • params – Parameters to configure this instance. See beluga::LikelihoodFieldModelBase 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 likelihood_field_origin() const

Returns the origin of the likelihood field in world coordinates.

inline void update_map(const map_type &grid)

Update the sensor model with a new occupancy grid map.

This method re-computes the underlying likelihood field.

Parameters:

grid – New occupancy grid representing the static map.

Protected Attributes

param_type params_

Parameters configuring the likelihood field model.

ValueGrid2<float> likelihood_field_

Likelihood field computed from the occupancy grid map.

Sophus::SE2d world_to_likelihood_field_transform_

Transformation from world coordinates to the likelihood field coordinate system.

Protected Static Functions

static inline ValueGrid2<float> make_likelihood_field(const param_type &params, const OccupancyGrid &grid)

Creates a likelihood field from an occupancy grid.

Parameters:
  • params – Parameters to configure the likelihood field.

  • grid – Occupancy grid representing the static map.

Returns:

Likelihood field computed from the occupancy grid.