Go to the documentation of this file.
17 #ifndef NDT__NDT_CONFIG_HPP_
18 #define NDT__NDT_CONFIG_HPP_
26 namespace localization
43 : m_map_config{std::forward<MapConfig>(
map_config)},
70 return m_guess_time_tol;
75 std::chrono::nanoseconds m_guess_time_tol;
87 : m_outlier_ratio{outlier_ratio} {}
112 const uint32_t scan_capacity,
113 std::chrono::nanoseconds guess_time_tolerance)
115 m_scan_capacity(scan_capacity) {}
121 return m_scan_capacity;
125 uint32_t m_scan_capacity;
132 #endif // NDT__NDT_CONFIG_HPP_
uint32_t scan_capacity() const noexcept
Definition: ndt_config.hpp:119
NDTLocalizerConfigBase(MapConfig &&map_config, std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:40
This file defines the configuration class for the voxel grid data structure.
float64_t Real
Definition: ndt_common.hpp:39
const MapConfig & map_config() const noexcept
Definition: ndt_config.hpp:61
NDTLocalizerConfigBase(const MapConfig &map_config, std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:50
perception::filters::voxel_grid::Config MapConfig
Definition: ndt_config.hpp:35
Config class for p2d optimziation problem.
Definition: ndt_config.hpp:80
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: ndt_config.hpp:32
Real outlier_ratio() const noexcept
Definition: ndt_config.hpp:91
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
P2DNDTLocalizerConfig(const MapConfig &map_config, const uint32_t scan_capacity, std::chrono::nanoseconds guess_time_tolerance)
Definition: ndt_config.hpp:110
P2DNDTOptimizationConfig(Real outlier_ratio)
Definition: ndt_config.hpp:86
const std::chrono::nanoseconds & guess_time_tolerance() const noexcept
Definition: ndt_config.hpp:68
config class for p2d ndt localizer
Definition: ndt_config.hpp:99