Template Class VDBLikelihoodFieldModel
Defined in File vdb_likelihood_field_model.hpp
Class Documentation
-
template<typename GridT, typename PointCloud, class StateType = Sophus::SE3d>
class VDBLikelihoodFieldModel 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 SensorModelPage.
- Template Parameters:
OpenVDB – grid type.
Public Types
-
using weight_type = double
Weight type of the particle.
-
using measurement_type = PointCloud
Measurement type given by the interface.
-
using param_type = VDBLikelihoodFieldModelParam
Parameter type that the constructor uses to configure the likelihood field model.
Public Functions
-
inline explicit VDBLikelihoodFieldModel(const param_type ¶ms, const map_type &grid)
Constructs a VDBLikelihoodFieldModel instance.
- Parameters:
params – Parameters to configure this instance. See beluga::VDBLikelihoodFieldModelParam for details.
grid – Narrow band Level set 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. Currently only supports OpenVDB Level sets.
-
inline auto operator()(measurement_type &&measurement) const
Returns a state weighting function conditioned on 3D lidar hits.
- Parameters:
measurement – 3D lidar measurement containing the hit points and the transform to the origin.
- Returns:
a state weighting function satisfying StateWeightingFunctionPage and borrowing a reference to this sensor model (and thus their lifetime are bound).