Autoware.Auto
autoware::localization::ndt::VoxelViewBase< VoxelT, Derived > Class Template Reference

#include <ndt_voxel_view.hpp>

Inheritance diagram for autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >:
Collaboration diagram for autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >:

Public Types

using Point = Eigen::Vector3d
 
using Cov = Eigen::Matrix3d
 

Public Member Functions

 VoxelViewBase (const VoxelT &vx)
 
const Pointcentroid () const
 
const Covinverse_covariance () const
 
bool8_t usable () const noexcept
 
const VoxelT & get () const noexcept
 

Additional Inherited Members

- Protected Member Functions inherited from autoware::common::helper_functions::crtp< Derived >
const Derived & impl () const
 
Derived & impl ()
 

Detailed Description

template<typename VoxelT, typename Derived>
class autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >

Base CRTP interface for the voxel view. It assumes a cached centroid and inverse covariance are provided by the implementation. This interface does not contain a covariance access function as it's not directly needed for the gaussian term shared in ndt optimization problems. It should be noted that, as this is purely a view of an existing voxel, it should not outlive the voxel it is referring to.

Template Parameters
VoxelTType of voxel to view.
DerivedImplementation. Expected to be of type VoxelView<VoxelT>.

Member Typedef Documentation

◆ Cov

template<typename VoxelT , typename Derived >
using autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >::Cov = Eigen::Matrix3d

◆ Point

template<typename VoxelT , typename Derived >
using autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >::Point = Eigen::Vector3d

Constructor & Destructor Documentation

◆ VoxelViewBase()

template<typename VoxelT , typename Derived >
autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >::VoxelViewBase ( const VoxelT &  vx)
inlineexplicit

Member Function Documentation

◆ centroid()

template<typename VoxelT , typename Derived >
const Point& autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >::centroid ( ) const
inline

◆ get()

template<typename VoxelT , typename Derived >
const VoxelT& autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >::get ( ) const
inlinenoexcept

◆ inverse_covariance()

template<typename VoxelT , typename Derived >
const Cov& autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >::inverse_covariance ( ) const
inline

◆ usable()

template<typename VoxelT , typename Derived >
bool8_t autoware::localization::ndt::VoxelViewBase< VoxelT, Derived >::usable ( ) const
inlinenoexcept

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