Autoware.Auto
ndt_config.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_CONFIG_HPP_
18 #define NDT__NDT_CONFIG_HPP_
19 
20 #include <ndt/ndt_common.hpp>
21 #include <voxel_grid/config.hpp>
22 #include <utility>
23 
24 namespace autoware
25 {
26 namespace localization
27 {
28 namespace ndt
29 {
33 {
34 public:
38  std::chrono::nanoseconds guess_time_tolerance)
39  : m_guess_time_tol{guess_time_tolerance} {}
40 
43  const std::chrono::nanoseconds & guess_time_tolerance() const noexcept
44  {
45  return m_guess_time_tol;
46  }
47 
48 private:
49  std::chrono::nanoseconds m_guess_time_tol;
50 };
51 
52 
54 class NDT_PUBLIC P2DNDTOptimizationConfig
55 {
56 public:
60  explicit P2DNDTOptimizationConfig(Real outlier_ratio)
61  : m_outlier_ratio{outlier_ratio} {}
62 
65  Real outlier_ratio() const noexcept {return m_outlier_ratio;}
66 
67 private:
68  Real m_outlier_ratio;
69 };
70 
71 
74 {
75 public:
82  const uint32_t scan_capacity,
83  std::chrono::nanoseconds guess_time_tolerance)
84  : NDTLocalizerConfigBase{guess_time_tolerance},
85  m_scan_capacity(scan_capacity) {}
86 
89  uint32_t scan_capacity() const noexcept
90  {
91  return m_scan_capacity;
92  }
93 
94 private:
95  uint32_t m_scan_capacity;
96 };
97 
98 } // namespace ndt
99 } // namespace localization
100 } // namespace autoware
101 
102 #endif // NDT__NDT_CONFIG_HPP_
NDTLocalizerConfigBase(std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:37
P2DNDTOptimizationConfig(Real outlier_ratio)
Definition: ndt_config.hpp:60
Real outlier_ratio() const noexcept
Definition: ndt_config.hpp:65
Config class for p2d optimziation problem.
Definition: ndt_config.hpp:54
float64_t Real
Definition: ndt_common.hpp:39
config class for p2d ndt localizer
Definition: ndt_config.hpp:73
P2DNDTLocalizerConfig(const uint32_t scan_capacity, std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:81
This file defines the configuration class for the voxel grid data structure.
uint32_t scan_capacity() const noexcept
Definition: ndt_config.hpp:89
const std::chrono::nanoseconds & guess_time_tolerance() const noexcept
Definition: ndt_config.hpp:43
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24