Public Types | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
beluga::DifferentialDriveModel< StateType > Class Template Reference

Sampled odometry model for a differential drive. More...

#include <differential_drive_model.hpp>

Public Types

using control_type = std::tuple< state_type, state_type >
 Current and previous odometry estimates as motion model control action. More...
 
using param_type = DifferentialDriveModelParam
 Parameter type that the constructor uses to configure the motion model. More...
 
using state_type = StateType
 2D or flattened 3D pose as motion model state (to match that of the particles). More...
 

Public Member Functions

 DifferentialDriveModel (const param_type &params)
 Constructs a DifferentialDriveModel instance. More...
 
template<class Control , typename = common_tuple_type_t<Control, control_type>>
auto operator() (const Control &action) const
 Computes a state sampling function conditioned on a given control action. More...
 

Private Types

using control_type_2d = std::tuple< Sophus::SE2d, Sophus::SE2d >
 
using control_type_3d = std::tuple< Sophus::SE3d, Sophus::SE3d >
 

Private Member Functions

auto sampling_fn_2d (const Sophus::SE2d &pose, const Sophus::SE2d &previous_pose) const
 
auto sampling_fn_3d (const Sophus::SE3d &pose, const Sophus::SE3d &previous_pose) const
 

Static Private Member Functions

static double rotation_variance (const Sophus::SO2d &rotation)
 

Private Attributes

param_type params_
 

Detailed Description

template<class StateType = Sophus::SE2d>
class beluga::DifferentialDriveModel< StateType >

Sampled odometry model for a differential drive.

Supports 2D and (flattened) 3D state types. This class satisfies Beluga named requirements: MotionModel.

See Probabilistic Robotics [thrun2005probabilistic] Chapter 5.4.2.

Template Parameters
StateTypeType for particle's state. Either Sophus::SE2d or Sophus::SE3d.

Definition at line 80 of file differential_drive_model.hpp.

Member Typedef Documentation

◆ control_type

template<class StateType = Sophus::SE2d>
using beluga::DifferentialDriveModel< StateType >::control_type = std::tuple<state_type, state_type>

Current and previous odometry estimates as motion model control action.

Definition at line 90 of file differential_drive_model.hpp.

◆ control_type_2d

template<class StateType = Sophus::SE2d>
using beluga::DifferentialDriveModel< StateType >::control_type_2d = std::tuple<Sophus::SE2d, Sophus::SE2d>
private

Definition at line 119 of file differential_drive_model.hpp.

◆ control_type_3d

template<class StateType = Sophus::SE2d>
using beluga::DifferentialDriveModel< StateType >::control_type_3d = std::tuple<Sophus::SE3d, Sophus::SE3d>
private

Definition at line 120 of file differential_drive_model.hpp.

◆ param_type

template<class StateType = Sophus::SE2d>
using beluga::DifferentialDriveModel< StateType >::param_type = DifferentialDriveModelParam

Parameter type that the constructor uses to configure the motion model.

Definition at line 93 of file differential_drive_model.hpp.

◆ state_type

template<class StateType = Sophus::SE2d>
using beluga::DifferentialDriveModel< StateType >::state_type = StateType

2D or flattened 3D pose as motion model state (to match that of the particles).

Definition at line 87 of file differential_drive_model.hpp.

Constructor & Destructor Documentation

◆ DifferentialDriveModel()

template<class StateType = Sophus::SE2d>
beluga::DifferentialDriveModel< StateType >::DifferentialDriveModel ( const param_type params)
inlineexplicit

Constructs a DifferentialDriveModel instance.

Parameters
paramsParameters to configure this instance. See beluga::DifferentialDriveModelParam for details.

Definition at line 100 of file differential_drive_model.hpp.

Member Function Documentation

◆ operator()()

template<class StateType = Sophus::SE2d>
template<class Control , typename = common_tuple_type_t<Control, control_type>>
auto beluga::DifferentialDriveModel< StateType >::operator() ( const Control &  action) const
inline

Computes a state sampling function conditioned on a given control action.

Template Parameters
ControlA tuple-like container matching the model's control_type.
Parameters
actionControl action to condition the motion model with.
Returns
a callable satisfying Beluga named requirements: StateSamplingFunction.

Definition at line 109 of file differential_drive_model.hpp.

◆ rotation_variance()

template<class StateType = Sophus::SE2d>
static double beluga::DifferentialDriveModel< StateType >::rotation_variance ( const Sophus::SO2d rotation)
inlinestaticprivate

Definition at line 167 of file differential_drive_model.hpp.

◆ sampling_fn_2d()

template<class StateType = Sophus::SE2d>
auto beluga::DifferentialDriveModel< StateType >::sampling_fn_2d ( const Sophus::SE2d pose,
const Sophus::SE2d previous_pose 
) const
inlineprivate

Definition at line 129 of file differential_drive_model.hpp.

◆ sampling_fn_3d()

template<class StateType = Sophus::SE2d>
auto beluga::DifferentialDriveModel< StateType >::sampling_fn_3d ( const Sophus::SE3d pose,
const Sophus::SE3d previous_pose 
) const
inlineprivate

Definition at line 122 of file differential_drive_model.hpp.

Member Data Documentation

◆ params_

template<class StateType = Sophus::SE2d>
param_type beluga::DifferentialDriveModel< StateType >::params_
private

Definition at line 165 of file differential_drive_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