17 #ifndef NDT__NDT_CONFIG_HPP_ 18 #define NDT__NDT_CONFIG_HPP_ 26 namespace localization
39 : m_guess_time_tol{guess_time_tolerance} {}
45 return m_guess_time_tol;
49 std::chrono::nanoseconds m_guess_time_tol;
61 : m_outlier_ratio{outlier_ratio} {}
82 const uint32_t scan_capacity,
85 m_scan_capacity(scan_capacity) {}
91 return m_scan_capacity;
95 uint32_t m_scan_capacity;
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
Definition: ndt_config.hpp:32
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