From 4420b11aacf0b21538a3159e1ccac54baa533e46 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Wed, 5 Jun 2024 16:51:56 +0900 Subject: [PATCH] initilize param Signed-off-by: Yamato Ando --- .../ndt_scan_matcher/hyper_parameters.hpp | 64 +++++++++---------- 1 file changed, 32 insertions(+), 32 deletions(-) diff --git a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp index bc7bf1fe40d36..7002b4bf43a73 100644 --- a/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp +++ b/localization/ndt_scan_matcher/include/ndt_scan_matcher/hyper_parameters.hpp @@ -33,62 +33,62 @@ struct HyperParameters { struct Frame { - std::string base_frame; - std::string ndt_base_frame; - std::string map_frame; - } frame; + std::string base_frame{}; + std::string ndt_base_frame{}; + std::string map_frame{}; + } frame{}; struct SensorPoints { - double required_distance; - } sensor_points; + double required_distance{}; + } sensor_points{}; - pclomp::NdtParams ndt; - bool ndt_regularization_enable; + pclomp::NdtParams ndt{}; + bool ndt_regularization_enable{}; struct InitialPoseEstimation { - int64_t particles_num; - int64_t n_startup_trials; - } initial_pose_estimation; + int64_t particles_num{}; + int64_t n_startup_trials{}; + } initial_pose_estimation{}; struct Validation { - double lidar_topic_timeout_sec; - double initial_pose_timeout_sec; - double initial_pose_distance_tolerance_m; - double critical_upper_bound_exe_time_ms; - } validation; + double lidar_topic_timeout_sec{}; + double initial_pose_timeout_sec{}; + double initial_pose_distance_tolerance_m{}; + double critical_upper_bound_exe_time_ms{}; + } validation{}; struct ScoreEstimation { - ConvergedParamType converged_param_type; - double converged_param_transform_probability; - double converged_param_nearest_voxel_transformation_likelihood; + ConvergedParamType converged_param_type{}; + double converged_param_transform_probability{}; + double converged_param_nearest_voxel_transformation_likelihood{}; struct NoGroundPoints { - bool enable; - double z_margin_for_ground_removal; - } no_ground_points; - } score_estimation; + bool enable{}; + double z_margin_for_ground_removal{}; + } no_ground_points{}; + } score_estimation{}; struct Covariance { - std::array output_pose_covariance; + std::array output_pose_covariance{}; struct CovarianceEstimation { - bool enable; - std::vector initial_pose_offset_model; - } covariance_estimation; - } covariance; + bool enable{}; + std::vector initial_pose_offset_model{}; + } covariance_estimation{}; + } covariance{}; struct DynamicMapLoading { - double update_distance; - double map_radius; - double lidar_radius; - } dynamic_map_loading; + double update_distance{}; + double map_radius{}; + double lidar_radius{}; + } dynamic_map_loading{}; public: explicit HyperParameters(rclcpp::Node * node)