@@ -37,24 +37,22 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
37
37
{
38
38
// set initial parameters
39
39
{
40
- low_priority_region_x_ = static_cast <float >(declare_parameter (" low_priority_region_x" , -20 .0f ));
41
- detection_range_z_max_ = static_cast <float >(declare_parameter (" detection_range_z_max" , 2 .5f ));
42
- center_pcl_shift_ = static_cast <float >(declare_parameter (" center_pcl_shift" , 0.0 ));
43
- non_ground_height_threshold_ =
44
- static_cast <float >(declare_parameter (" non_ground_height_threshold" , 0.20 ));
45
- grid_mode_switch_radius_ =
46
- static_cast <float >(declare_parameter (" grid_mode_switch_radius" , 20.0 ));
47
-
48
- grid_size_m_ = static_cast <float >(declare_parameter (" grid_size_m" , 0.5 ));
49
- gnd_grid_buffer_size_ = static_cast <int >(declare_parameter (" gnd_grid_buffer_size" , 4 ));
50
- elevation_grid_mode_ = static_cast <bool >(declare_parameter (" elevation_grid_mode" , true ));
51
- global_slope_max_angle_rad_ = deg2rad (declare_parameter (" global_slope_max_angle_deg" , 8.0 ));
52
- local_slope_max_angle_rad_ = deg2rad (declare_parameter (" local_slope_max_angle_deg" , 10.0 ));
53
- radial_divider_angle_rad_ = deg2rad (declare_parameter (" radial_divider_angle_deg" , 1.0 ));
54
- split_points_distance_tolerance_ = declare_parameter (" split_points_distance_tolerance" , 0.2 );
55
- split_height_distance_ = declare_parameter (" split_height_distance" , 0.2 );
56
- use_virtual_ground_point_ = declare_parameter (" use_virtual_ground_point" , true );
57
- use_recheck_ground_cluster_ = declare_parameter (" use_recheck_ground_cluster" , true );
40
+ low_priority_region_x_ = declare_parameter<float >(" low_priority_region_x" );
41
+ detection_range_z_max_ = declare_parameter<float >(" detection_range_z_max" );
42
+ center_pcl_shift_ = declare_parameter<float >(" center_pcl_shift" );
43
+ non_ground_height_threshold_ = declare_parameter<float >(" non_ground_height_threshold" );
44
+ grid_mode_switch_radius_ = declare_parameter<float >(" grid_mode_switch_radius" );
45
+
46
+ grid_size_m_ = declare_parameter<float >(" grid_size_m" );
47
+ gnd_grid_buffer_size_ = declare_parameter<int >(" gnd_grid_buffer_size" );
48
+ elevation_grid_mode_ = declare_parameter<bool >(" elevation_grid_mode" );
49
+ global_slope_max_angle_rad_ = deg2rad (declare_parameter<float >(" global_slope_max_angle_deg" ));
50
+ local_slope_max_angle_rad_ = deg2rad (declare_parameter<float >(" local_slope_max_angle_deg" ));
51
+ radial_divider_angle_rad_ = deg2rad (declare_parameter<float >(" radial_divider_angle_deg" ));
52
+ split_points_distance_tolerance_ = declare_parameter<float >(" split_points_distance_tolerance" );
53
+ split_height_distance_ = declare_parameter<float >(" split_height_distance" );
54
+ use_virtual_ground_point_ = declare_parameter<bool >(" use_virtual_ground_point" );
55
+ use_recheck_ground_cluster_ = declare_parameter<bool >(" use_recheck_ground_cluster" );
58
56
radial_dividers_num_ = std::ceil (2.0 * M_PI / radial_divider_angle_rad_);
59
57
vehicle_info_ = VehicleInfoUtil (*this ).getVehicleInfo ();
60
58
0 commit comments