17 #ifndef NDT__NDT_VOXEL_HPP_ 18 #define NDT__NDT_VOXEL_HPP_ 21 #include <experimental/optional> 29 namespace localization
48 using Cov = Eigen::Matrix3d;
53 static constexpr uint32_t NUM_POINT_THRESHOLD = 3U;
59 void add_observation(
const Point & pt);
67 bool8_t usable() const noexcept;
73 const
Cov & covariance() const;
78 std::experimental::optional<
Cov> inverse_covariance() const;
82 const
Point & centroid() const;
86 uint64_t count() const noexcept;
93 uint64_t m_num_points{0U};
102 using Cov = Eigen::Matrix3d;
113 Cov covariance()
const;
116 const Point & centroid()
const;
120 const Cov & inverse_covariance()
const;
124 bool8_t usable() const noexcept;
128 Cov m_inv_covariance;
135 #endif // NDT__NDT_VOXEL_HPP_ Eigen::Matrix3d Cov
Definition: ndt_voxel.hpp:48
Definition: ndt_voxel.hpp:44
bool bool8_t
Definition: types.hpp:33
This file includes common type definition.
Invertibility
Definition: ndt_voxel.hpp:34
This file defines children and specializations of the Voxel class.
Eigen::Matrix3d Cov
Definition: ndt_voxel.hpp:102
Definition: ndt_voxel.hpp:98
Eigen::Vector3d Point
Definition: ndt_voxel.hpp:47
Eigen::Vector3d Point
Definition: ndt_voxel.hpp:101
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24