Skip to content

Commit

Permalink
initilize param
Browse files Browse the repository at this point in the history
Signed-off-by: Yamato Ando <[email protected]>
  • Loading branch information
YamatoAndo committed Jun 5, 2024
1 parent 70267b5 commit 4420b11
Showing 1 changed file with 32 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<double, 36> output_pose_covariance;
std::array<double, 36> output_pose_covariance{};

struct CovarianceEstimation
{
bool enable;
std::vector<Eigen::Vector2d> initial_pose_offset_model;
} covariance_estimation;
} covariance;
bool enable{};
std::vector<Eigen::Vector2d> 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)
Expand Down

0 comments on commit 4420b11

Please sign in to comment.