Go to the documentation of this file.
17 #ifndef NDT__NDT_VOXEL_VIEW_HPP_
18 #define NDT__NDT_VOXEL_VIEW_HPP_
24 namespace localization
29 template<
typename VoxelT>
40 template<
typename VoxelT,
typename Derived>
45 using Cov = Eigen::Matrix3d;
51 return this->impl().centroid_();
55 return this->impl().inverse_covariance_();
59 return this->impl().usable_();
61 const VoxelT &
get() const noexcept
67 const VoxelT & m_data_ref;
73 :
public VoxelViewBase<StaticNDTVoxel, VoxelView<StaticNDTVoxel>>
77 using Cov = Eigen::Matrix3d;
81 const Cov & inverse_covariance_()
const;
82 const Point & centroid_()
const;
83 bool8_t usable_() const noexcept;
101 using Cov = Eigen::Matrix3d;
104 const Cov & inverse_covariance_()
const;
105 const Point & centroid_()
const;
106 bool8_t usable_() const noexcept;
109 Cov m_inverse_covariance;
118 #endif // NDT__NDT_VOXEL_VIEW_HPP_
const Point & centroid() const
Definition: ndt_voxel_view.hpp:49
Eigen::Vector3d Point
Definition: ndt_voxel_view.hpp:76
Definition: ndt_voxel_view.hpp:41
VoxelViewBase(const VoxelT &vx)
Definition: ndt_voxel_view.hpp:46
Eigen::Matrix3d Cov
Definition: ndt_voxel_view.hpp:45
Eigen::Matrix3d Cov
Definition: ndt_voxel_view.hpp:101
Eigen::Vector3d Point
Definition: ndt_voxel_view.hpp:100
Definition: ndt_voxel.hpp:101
bool8_t usable() const noexcept
Definition: ndt_voxel_view.hpp:57
bool bool8_t
Definition: types.hpp:39
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
class NDT_PUBLIC VoxelView
Definition: ndt_voxel_view.hpp:30
Eigen::Matrix3d Cov
Definition: ndt_voxel_view.hpp:77
Definition: ndt_voxel.hpp:46
const Cov & inverse_covariance() const
Definition: ndt_voxel_view.hpp:53
Eigen::Vector3d Point
Definition: ndt_voxel_view.hpp:44
const VoxelT & get() const noexcept
Definition: ndt_voxel_view.hpp:61