Public Types | Public Member Functions | Private Attributes | List of all members
beluga::BearingSensorModel< LandmarkMap, StateType > Class Template Reference

Generic bearing sensor model, for both 2D and 3D state types. More...

#include <bearing_sensor_model.hpp>

Public Types

using map_type = LandmarkMap
 Map representation type. More...
 
using measurement_type = std::vector< LandmarkBearingDetection >
 Measurement type of the sensor: vector of landmark detections. More...
 
using param_type = BearingModelParam
 Parameter type that the constructor uses to configure the bearing sensor model. More...
 
using state_type = StateType
 State type of a particle. More...
 
using weight_type = double
 Weight type of the particle. More...
 

Public Member Functions

template<class... Args>
 BearingSensorModel (param_type params, LandmarkMap landmark_map)
 Constructs a BearingSensorModel instance. More...
 
auto operator() (measurement_type &&detections) const
 Returns a state weighting function conditioned on landmark bearing detections. More...
 
void update_map (map_type &&map)
 Update the sensor model with a new landmark map. More...
 

Private Attributes

LandmarkMap landmark_map_
 
param_type params_
 

Detailed Description

template<class LandmarkMap, class StateType>
class beluga::BearingSensorModel< LandmarkMap, StateType >

Generic bearing sensor model, for both 2D and 3D state types.

The model only relies on the bearing of a landmark detection relative to the sensor when calculating the updated importance weight. This can be used to support bearing-only measurements, such as feature detections in monocular images.

Note
This class satisfies Beluga named requirements: SensorModel.
Template Parameters
LandmarkMapclass managing the list of known landmarks.
StateTypetype of the state of the particle.

Definition at line 60 of file bearing_sensor_model.hpp.

Member Typedef Documentation

◆ map_type

template<class LandmarkMap , class StateType >
using beluga::BearingSensorModel< LandmarkMap, StateType >::map_type = LandmarkMap

Map representation type.

Definition at line 69 of file bearing_sensor_model.hpp.

◆ measurement_type

template<class LandmarkMap , class StateType >
using beluga::BearingSensorModel< LandmarkMap, StateType >::measurement_type = std::vector<LandmarkBearingDetection>

Measurement type of the sensor: vector of landmark detections.

Definition at line 67 of file bearing_sensor_model.hpp.

◆ param_type

template<class LandmarkMap , class StateType >
using beluga::BearingSensorModel< LandmarkMap, StateType >::param_type = BearingModelParam

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

Definition at line 71 of file bearing_sensor_model.hpp.

◆ state_type

template<class LandmarkMap , class StateType >
using beluga::BearingSensorModel< LandmarkMap, StateType >::state_type = StateType

State type of a particle.

Definition at line 63 of file bearing_sensor_model.hpp.

◆ weight_type

template<class LandmarkMap , class StateType >
using beluga::BearingSensorModel< LandmarkMap, StateType >::weight_type = double

Weight type of the particle.

Definition at line 65 of file bearing_sensor_model.hpp.

Constructor & Destructor Documentation

◆ BearingSensorModel()

template<class LandmarkMap , class StateType >
template<class... Args>
beluga::BearingSensorModel< LandmarkMap, StateType >::BearingSensorModel ( param_type  params,
LandmarkMap  landmark_map 
)
inlineexplicit

Constructs a BearingSensorModel instance.

Parameters
paramsParameters to configure this instance. See beluga::BearingModelParam for details.
landmark_mapMap of landmarks to be used by the sensor model to compute importance weights for particle states.

Definition at line 80 of file bearing_sensor_model.hpp.

Member Function Documentation

◆ operator()()

template<class LandmarkMap , class StateType >
auto beluga::BearingSensorModel< LandmarkMap, StateType >::operator() ( measurement_type &&  detections) const
inline

Returns a state weighting function conditioned on landmark bearing detections.

Parameters
detectionsLandmark bearing detections 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 89 of file bearing_sensor_model.hpp.

◆ update_map()

template<class LandmarkMap , class StateType >
void beluga::BearingSensorModel< LandmarkMap, StateType >::update_map ( map_type &&  map)
inline

Update the sensor model with a new landmark map.

Definition at line 144 of file bearing_sensor_model.hpp.

Member Data Documentation

◆ landmark_map_

template<class LandmarkMap , class StateType >
LandmarkMap beluga::BearingSensorModel< LandmarkMap, StateType >::landmark_map_
private

Definition at line 148 of file bearing_sensor_model.hpp.

◆ params_

template<class LandmarkMap , class StateType >
param_type beluga::BearingSensorModel< LandmarkMap, StateType >::params_
private

Definition at line 147 of file bearing_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