Public Types | Public Member Functions | Private Attributes | List of all members
beluga::NDTSensorModel< SparseGridT > Class Template Reference

NDT sensor model for range finders. More...

#include <ndt_sensor_model.hpp>

Public Types

using map_type = SparseGridT
 Map representation type. More...
 
using measurement_type = std::vector< Eigen::Vector< typename ndt_cell_type::scalar_type, ndt_cell_type::num_dim > >
 Measurement type of the sensor: a point cloud for the range finder. More...
 
using ndt_cell_type = typename SparseGridT::mapped_type
 NDT Cell type. More...
 
using param_type = NDTModelParam< ndt_cell_type::num_dim >
 Parameter type that the constructor uses to configure the NDT sensor model. More...
 
using state_type = std::conditional_t< ndt_cell_type::num_dim==2, Sophus::SE2< typename ndt_cell_type::scalar_type >, Sophus::SE3< typename ndt_cell_type::scalar_type > >
 State type of a particle. More...
 
using weight_type = double
 Weight type of the particle. More...
 

Public Member Functions

double likelihood_at (const ndt_cell_type &measurement) const
 
 NDTSensorModel (param_type params, SparseGridT cells_data)
 Constructs a NDTSensorModel instance. More...
 
auto operator() (measurement_type &&points) const
 Returns a state weighting function conditioned on 2D / 3D lidar hits. More...
 

Private Attributes

const SparseGridT cells_data_
 
const param_type params_
 

Detailed Description

template<typename SparseGridT>
class beluga::NDTSensorModel< SparseGridT >

NDT sensor model for range finders.

This class satisfies Beluga named requirements: SensorModel.

Template Parameters
SparseGridTType representing a sparse NDT grid, as a specialization of 'beluga::SparseValueGrid'.

Definition at line 172 of file ndt_sensor_model.hpp.

Member Typedef Documentation

◆ map_type

template<typename SparseGridT >
using beluga::NDTSensorModel< SparseGridT >::map_type = SparseGridT

Map representation type.

Definition at line 190 of file ndt_sensor_model.hpp.

◆ measurement_type

template<typename SparseGridT >
using beluga::NDTSensorModel< SparseGridT >::measurement_type = std::vector<Eigen::Vector<typename ndt_cell_type::scalar_type, ndt_cell_type::num_dim> >

Measurement type of the sensor: a point cloud for the range finder.

Definition at line 188 of file ndt_sensor_model.hpp.

◆ ndt_cell_type

template<typename SparseGridT >
using beluga::NDTSensorModel< SparseGridT >::ndt_cell_type = typename SparseGridT::mapped_type

NDT Cell type.

Definition at line 175 of file ndt_sensor_model.hpp.

◆ param_type

template<typename SparseGridT >
using beluga::NDTSensorModel< SparseGridT >::param_type = NDTModelParam<ndt_cell_type::num_dim>

Parameter type that the constructor uses to configure the NDT sensor model.

Definition at line 192 of file ndt_sensor_model.hpp.

◆ state_type

template<typename SparseGridT >
using beluga::NDTSensorModel< SparseGridT >::state_type = std::conditional_t< ndt_cell_type::num_dim == 2, Sophus::SE2<typename ndt_cell_type::scalar_type>, Sophus::SE3<typename ndt_cell_type::scalar_type> >

State type of a particle.

Definition at line 184 of file ndt_sensor_model.hpp.

◆ weight_type

template<typename SparseGridT >
using beluga::NDTSensorModel< SparseGridT >::weight_type = double

Weight type of the particle.

Definition at line 186 of file ndt_sensor_model.hpp.

Constructor & Destructor Documentation

◆ NDTSensorModel()

template<typename SparseGridT >
beluga::NDTSensorModel< SparseGridT >::NDTSensorModel ( param_type  params,
SparseGridT  cells_data 
)
inline

Constructs a NDTSensorModel instance.

Parameters
paramsParameters to configure this instance. See beluga::NDTModelParam for details.
cells_dataSparse grid representing an NDT map, used for calculating importance weights for the different particles.

Definition at line 201 of file ndt_sensor_model.hpp.

Member Function Documentation

◆ likelihood_at()

template<typename SparseGridT >
double beluga::NDTSensorModel< SparseGridT >::likelihood_at ( const ndt_cell_type measurement) const
inline

Returns the L2 likelihood scaled by 'd1' and 'd2' set in the parameters for this instance for 'measurement', for the neighbors kernel cells around the measurement cell, or 'params_.min_likelihood', whichever is higher.

Definition at line 223 of file ndt_sensor_model.hpp.

◆ operator()()

template<typename SparseGridT >
auto beluga::NDTSensorModel< SparseGridT >::operator() ( measurement_type &&  points) const
inline

Returns a state weighting function conditioned on 2D / 3D lidar hits.

Parameters
pointsLidar 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).

Definition at line 212 of file ndt_sensor_model.hpp.

Member Data Documentation

◆ cells_data_

template<typename SparseGridT >
const SparseGridT beluga::NDTSensorModel< SparseGridT >::cells_data_
private

Definition at line 237 of file ndt_sensor_model.hpp.

◆ params_

template<typename SparseGridT >
const param_type beluga::NDTSensorModel< SparseGridT >::params_
private

Definition at line 236 of file ndt_sensor_model.hpp.


The documentation for this class was generated from the following file:


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