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:
36 
42  std::chrono::nanoseconds guess_time_tolerance)
43  : m_map_config{std::forward<MapConfig>(map_config)},
44  m_guess_time_tol{guess_time_tolerance} {}
45 
51  const MapConfig & map_config,
52  std::chrono::nanoseconds guess_time_tolerance)
53  : m_map_config{map_config},
54  m_guess_time_tol{guess_time_tolerance}
55  {}
56 
57  // TODO(yunus.caliskan): Consider delegating map config get/set to the implementation
58  // when map types with different configuration needs are added.
61  const MapConfig & map_config() const noexcept
62  {
63  return m_map_config;
64  }
65 
68  const std::chrono::nanoseconds & guess_time_tolerance() const noexcept
69  {
70  return m_guess_time_tol;
71  }
72 
73 private:
74  MapConfig m_map_config;
75  std::chrono::nanoseconds m_guess_time_tol;
76 };
77 
78 
80 class NDT_PUBLIC P2DNDTOptimizationConfig
81 {
82 public:
86  explicit P2DNDTOptimizationConfig(Real outlier_ratio)
87  : m_outlier_ratio{outlier_ratio} {}
88 
91  Real outlier_ratio() const noexcept {return m_outlier_ratio;}
92 
93 private:
94  Real m_outlier_ratio;
95 };
96 
97 
100 {
101 public:
103 
111  const MapConfig & map_config,
112  const uint32_t scan_capacity,
113  std::chrono::nanoseconds guess_time_tolerance)
114  : NDTLocalizerConfigBase{map_config, guess_time_tolerance},
115  m_scan_capacity(scan_capacity) {}
116 
119  uint32_t scan_capacity() const noexcept
120  {
121  return m_scan_capacity;
122  }
123 
124 private:
125  uint32_t m_scan_capacity;
126 };
127 
128 } // namespace ndt
129 } // namespace localization
130 } // namespace autoware
131 
132 #endif // NDT__NDT_CONFIG_HPP_
autoware::localization::ndt::P2DNDTLocalizerConfig::scan_capacity
uint32_t scan_capacity() const noexcept
Definition: ndt_config.hpp:119
autoware::localization::ndt::NDTLocalizerConfigBase::NDTLocalizerConfigBase
NDTLocalizerConfigBase(MapConfig &&map_config, std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:40
config.hpp
This file defines the configuration class for the voxel grid data structure.
autoware::localization::ndt::Real
float64_t Real
Definition: ndt_common.hpp:39
autoware::localization::ndt::NDTLocalizerConfigBase::map_config
const MapConfig & map_config() const noexcept
Definition: ndt_config.hpp:61
autoware::localization::ndt::NDTLocalizerConfigBase::NDTLocalizerConfigBase
NDTLocalizerConfigBase(const MapConfig &map_config, std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:50
autoware::localization::ndt::NDTLocalizerConfigBase::MapConfig
perception::filters::voxel_grid::Config MapConfig
Definition: ndt_config.hpp:35
autoware::localization::ndt::P2DNDTOptimizationConfig
Config class for p2d optimziation problem.
Definition: ndt_config.hpp:80
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
ndt_common.hpp
autoware::localization::ndt::NDTLocalizerConfigBase
Definition: ndt_config.hpp:32
autoware::localization::ndt::P2DNDTOptimizationConfig::outlier_ratio
Real outlier_ratio() const noexcept
Definition: ndt_config.hpp:91
autoware::perception::filters::voxel_grid::Config
A configuration class for the VoxelGrid data structure, also includes some helper functionality for c...
Definition: perception/filters/voxel_grid/include/voxel_grid/config.hpp:52
autoware::localization::ndt::P2DNDTLocalizerConfig::P2DNDTLocalizerConfig
P2DNDTLocalizerConfig(const MapConfig &map_config, const uint32_t scan_capacity, std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:110
autoware::localization::ndt::P2DNDTOptimizationConfig::P2DNDTOptimizationConfig
P2DNDTOptimizationConfig(Real outlier_ratio)
Definition: ndt_config.hpp:86
autoware::localization::ndt::NDTLocalizerConfigBase::guess_time_tolerance
const std::chrono::nanoseconds & guess_time_tolerance() const noexcept
Definition: ndt_config.hpp:68
autoware::localization::ndt::P2DNDTLocalizerConfig
config class for p2d ndt localizer
Definition: ndt_config.hpp:99