Autoware.Auto
ndt_voxel.hpp
Go to the documentation of this file.
1 // Copyright 2019-2021 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_HPP_
18 #define NDT__NDT_VOXEL_HPP_
19 
20 #include <common/types.hpp>
21 #include <experimental/optional>
22 #include <ndt/ndt_common.hpp>
23 #include <voxel_grid/voxels.hpp>
24 
25 #include <Eigen/Core>
26 
28 
29 namespace autoware
30 {
31 namespace localization
32 {
33 namespace ndt
34 {
35 
36 enum class Invertibility
37 {
38  INVERTIBLE,
40  UNKNOWN
41 };
42 
46 class NDT_PUBLIC DynamicNDTVoxel
47 {
48 public:
49  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50  using Point = Eigen::Vector3d;
51  using Cov = Eigen::Matrix3d;
53 
54  // TODO(yunus.caliskan): make this configurable.
55  // Number of points a voxel should have to count as occupied. Set to the dimension of a 3D point.
56  static constexpr uint32_t NUM_POINT_THRESHOLD = 3U;
57 
62  void add_observation(const Point & pt);
63 
66  bool8_t try_stabilize();
67 
70  bool8_t usable() const noexcept;
71 
76  const Cov & covariance() const;
77 
81  std::experimental::optional<Cov> inverse_covariance() const;
82 
85  const Point & centroid() const;
86 
89  uint64_t count() const noexcept;
90 
91 private:
92  Point m_centroid;
93  Cov m_M2; // Used in covariance computation.
94  Cov m_covariance;
96  uint64_t m_num_points{0U};
97 };
98 
101 class NDT_PUBLIC StaticNDTVoxel
102 {
103 public:
104  using Point = Eigen::Vector3d;
105  using Cov = Eigen::Matrix3d;
107  StaticNDTVoxel();
108 
112  StaticNDTVoxel(const Point & centroid, const Cov & inv_covariance);
113 
116  Cov covariance() const;
119  const Point & centroid() const;
120 
123  const Cov & inverse_covariance() const;
124 
127  bool8_t usable() const noexcept;
128 
129 private:
130  Point m_centroid;
131  Cov m_inv_covariance;
132  bool8_t m_occupied{false};
133 };
134 } // namespace ndt
135 } // namespace localization
136 } // namespace autoware
137 
138 #endif // NDT__NDT_VOXEL_HPP_
autoware::localization::ndt::Invertibility::UNKNOWN
@ UNKNOWN
voxels.hpp
This file defines children and specializations of the Voxel class.
autoware::localization::ndt::StaticNDTVoxel::Point
Eigen::Vector3d Point
Definition: ndt_voxel.hpp:104
types.hpp
This file includes common type definition.
autoware::localization::ndt::Invertibility::NOT_INVERTIBLE
@ NOT_INVERTIBLE
autoware::localization::ndt::StaticNDTVoxel
Definition: ndt_voxel.hpp:101
autoware::localization::ndt::Invertibility
Invertibility
Definition: ndt_voxel.hpp:36
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
ndt_common.hpp
autoware::localization::ndt::StaticNDTVoxel::Cov
Eigen::Matrix3d Cov
Definition: ndt_voxel.hpp:105
autoware::localization::ndt::DynamicNDTVoxel
Definition: ndt_voxel.hpp:46
autoware::localization::ndt::DynamicNDTVoxel::Point
Eigen::Vector3d Point
Definition: ndt_voxel.hpp:50
autoware::localization::ndt::Invertibility::INVERTIBLE
@ INVERTIBLE
autoware::localization::ndt::DynamicNDTVoxel::Cov
Eigen::Matrix3d Cov
Definition: ndt_voxel.hpp:51