Autoware.Auto
ndt_voxel_view.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef NDT__NDT_VOXEL_VIEW_HPP_
18 #define NDT__NDT_VOXEL_VIEW_HPP_
19 
20 #include <ndt/ndt_voxel.hpp>
21 
22 namespace autoware
23 {
24 namespace localization
25 {
26 namespace ndt
27 {
28 
29 template<typename VoxelT>
30 class NDT_PUBLIC VoxelView;
31 
40 template<typename VoxelT, typename Derived>
41 class NDT_PUBLIC VoxelViewBase : public common::helper_functions::crtp<Derived>
42 {
43 public:
44  using Point = Eigen::Vector3d;
45  using Cov = Eigen::Matrix3d;
46  explicit VoxelViewBase(const VoxelT & vx)
47  : m_data_ref{vx} {}
48 
49  const Point & centroid() const
50  {
51  return this->impl().centroid_();
52  }
53  const Cov & inverse_covariance() const
54  {
55  return this->impl().inverse_covariance_();
56  }
57  bool8_t usable() const noexcept
58  {
59  return this->impl().usable_();
60  }
61  const VoxelT & get() const noexcept
62  {
63  return m_data_ref;
64  }
65 
66 private:
67  const VoxelT & m_data_ref;
68 };
69 
71 template<>
72 class NDT_PUBLIC VoxelView<StaticNDTVoxel>
73  : public VoxelViewBase<StaticNDTVoxel, VoxelView<StaticNDTVoxel>>
74 {
75 public:
76  using Point = Eigen::Vector3d;
77  using Cov = Eigen::Matrix3d;
79  explicit VoxelView(const StaticNDTVoxel & voxel);
80 
81  const Cov & inverse_covariance_() const;
82  const Point & centroid_() const;
83  bool8_t usable_() const noexcept;
84 
85 private:
86  bool8_t m_usable;
87 };
88 
89 
94 template<>
95 class NDT_PUBLIC VoxelView<DynamicNDTVoxel>
97 {
98 public:
100  using Point = Eigen::Vector3d;
101  using Cov = Eigen::Matrix3d;
102  explicit VoxelView(const DynamicNDTVoxel & voxel);
103 
104  const Cov & inverse_covariance_() const;
105  const Point & centroid_() const;
106  bool8_t usable_() const noexcept;
107 
108 private:
109  Cov m_inverse_covariance;
110  bool8_t m_usable{true};
111 };
112 
113 
114 } // namespace ndt
115 } // namespace localization
116 } // namespace autoware
117 
118 #endif // NDT__NDT_VOXEL_VIEW_HPP_
autoware::localization::ndt::VoxelViewBase::centroid
const Point & centroid() const
Definition: ndt_voxel_view.hpp:49
autoware::localization::ndt::VoxelView< StaticNDTVoxel >::Point
Eigen::Vector3d Point
Definition: ndt_voxel_view.hpp:76
autoware::localization::ndt::VoxelViewBase
Definition: ndt_voxel_view.hpp:41
autoware::localization::ndt::VoxelViewBase::VoxelViewBase
VoxelViewBase(const VoxelT &vx)
Definition: ndt_voxel_view.hpp:46
autoware::localization::ndt::VoxelViewBase< DynamicNDTVoxel, VoxelView< DynamicNDTVoxel > >::Cov
Eigen::Matrix3d Cov
Definition: ndt_voxel_view.hpp:45
autoware::localization::ndt::VoxelView< DynamicNDTVoxel >::Cov
Eigen::Matrix3d Cov
Definition: ndt_voxel_view.hpp:101
autoware::localization::ndt::VoxelView< DynamicNDTVoxel >::Point
Eigen::Vector3d Point
Definition: ndt_voxel_view.hpp:100
autoware::localization::ndt::StaticNDTVoxel
Definition: ndt_voxel.hpp:101
autoware::localization::ndt::VoxelViewBase::usable
bool8_t usable() const noexcept
Definition: ndt_voxel_view.hpp:57
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::VoxelView
class NDT_PUBLIC VoxelView
Definition: ndt_voxel_view.hpp:30
autoware::common::helper_functions::crtp
Definition: crtp.hpp:29
autoware::localization::ndt::VoxelView< StaticNDTVoxel >::Cov
Eigen::Matrix3d Cov
Definition: ndt_voxel_view.hpp:77
ndt_voxel.hpp
autoware::localization::ndt::DynamicNDTVoxel
Definition: ndt_voxel.hpp:46
autoware::localization::ndt::VoxelViewBase::inverse_covariance
const Cov & inverse_covariance() const
Definition: ndt_voxel_view.hpp:53
autoware::localization::ndt::VoxelViewBase< DynamicNDTVoxel, VoxelView< DynamicNDTVoxel > >::Point
Eigen::Vector3d Point
Definition: ndt_voxel_view.hpp:44
autoware::localization::ndt::VoxelViewBase::get
const VoxelT & get() const noexcept
Definition: ndt_voxel_view.hpp:61