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

Beam sensor model for range finders. More...

#include <beam_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 = BeamModelParam
 Parameter type that the constructor uses to configure the beam sensor 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

 BeamSensorModel (const param_type &params, OccupancyGrid grid)
 Constructs a BeamSensorModel instance. More...
 
auto operator() (measurement_type &&points) const
 Returns a state weighting function conditioned on 2D lidar hits. More...
 
void update_map (map_type &&map)
 Update the sensor model with a new occupancy grid map. More...
 

Private Attributes

OccupancyGrid grid_
 
param_type params_
 

Detailed Description

template<class OccupancyGrid>
class beluga::BeamSensorModel< OccupancyGrid >

Beam sensor model for range finders.

This model closely matches the physical behavior of a lidar, but it is computationally expensive because a ray-tracing operation needs to be performed for each particle and individual range reading. Also, this model can experience degraded performance in cluttered environments due the inherent lack of smoothness of the sensor readings in such settings. See Probabilistic Robotics [thrun2005probabilistic] Chapter 6.2 for further reference.

Note
This class satisfies Beluga named requirements: SensorModel.
Template Parameters
OccupancyGridType representing an occupancy grid. It must satisfy Beluga named requirements: OccupancyGrid2d.

Definition at line 75 of file beam_model.hpp.

Member Typedef Documentation

◆ map_type

template<class OccupancyGrid >
using beluga::BeamSensorModel< OccupancyGrid >::map_type = OccupancyGrid

Map representation type.

Definition at line 84 of file beam_model.hpp.

◆ measurement_type

template<class OccupancyGrid >
using beluga::BeamSensorModel< OccupancyGrid >::measurement_type = std::vector<std::pair<double, double> >

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

Definition at line 82 of file beam_model.hpp.

◆ param_type

template<class OccupancyGrid >
using beluga::BeamSensorModel< OccupancyGrid >::param_type = BeamModelParam

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

Definition at line 86 of file beam_model.hpp.

◆ state_type

template<class OccupancyGrid >
using beluga::BeamSensorModel< OccupancyGrid >::state_type = Sophus::SE2d

State type of a particle.

Definition at line 78 of file beam_model.hpp.

◆ weight_type

template<class OccupancyGrid >
using beluga::BeamSensorModel< OccupancyGrid >::weight_type = double

Weight type of the particle.

Definition at line 80 of file beam_model.hpp.

Constructor & Destructor Documentation

◆ BeamSensorModel()

template<class OccupancyGrid >
beluga::BeamSensorModel< OccupancyGrid >::BeamSensorModel ( const param_type params,
OccupancyGrid  grid 
)
inlineexplicit

Constructs a BeamSensorModel instance.

Parameters
paramsParameters to configure this instance. See beluga::BeamModelParams for details.
gridOccupancy grid representing the static map that the sensor model uses to raytrace lidar beams and compute importance weights for particle states.

Definition at line 95 of file beam_model.hpp.

Member Function Documentation

◆ operator()()

template<class OccupancyGrid >
auto beluga::BeamSensorModel< OccupancyGrid >::operator() ( measurement_type &&  points) const
inline

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

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

Definition at line 103 of file beam_model.hpp.

◆ update_map()

template<class OccupancyGrid >
void beluga::BeamSensorModel< OccupancyGrid >::update_map ( map_type &&  map)
inline

Update the sensor model with a new occupancy grid map.

Parameters
mapNew occupancy grid representing the static map.

Definition at line 155 of file beam_model.hpp.

Member Data Documentation

◆ grid_

template<class OccupancyGrid >
OccupancyGrid beluga::BeamSensorModel< OccupancyGrid >::grid_
private

Definition at line 159 of file beam_model.hpp.

◆ params_

template<class OccupancyGrid >
param_type beluga::BeamSensorModel< OccupancyGrid >::params_
private

Definition at line 158 of file beam_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