Skip to content

Commit 529c655

Browse files
committed
chore(ground_segmentation): rework params (autowarefoundation#6209)
* chore: remove default params Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: scan ground gtest Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: ray ground filter gtest Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 02e292b commit 529c655

13 files changed

+200
-72
lines changed

perception/ground_segmentation/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,7 @@ if(BUILD_TESTING)
8989

9090
target_link_libraries(test_ray_ground_filter
9191
ground_segmentation
92+
${YAML_CPP_LIBRARIES}
9293
)
9394

9495
ament_add_ros_isolated_gtest(test_scan_ground_filter

perception/ground_segmentation/config/ground_segmentation.param.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -29,3 +29,7 @@
2929
gnd_grid_buffer_size: 4
3030
detection_range_z_max: 2.5
3131
elevation_grid_mode: true
32+
low_priority_region_x: -20.0
33+
center_pcl_shift: 0.0
34+
radial_divider_angle_deg: 1.0
35+
use_recheck_ground_cluster: true
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
base_frame: "base_link"
4+
unit_axis: "z"
5+
max_iterations: 1000
6+
min_trial: 5000
7+
min_points: 1000
8+
outlier_threshold: 0.01
9+
plane_slope_threshold: 10.0
10+
voxel_size_x: 0.04
11+
voxel_size_y: 0.04
12+
voxel_size_z: 0.04
13+
height_threshold: 0.01
14+
debug: false
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
min_x: -0.01
4+
max_x: 0.01
5+
min_y: -0.01
6+
max_y: 0.01
7+
use_vehicle_footprint: false
8+
general_max_slope: 8.0
9+
local_max_slope: 6.0
10+
initial_max_slope: 3.0
11+
radial_divider_angle: 1.0
12+
min_height_threshold: 0.15
13+
concentric_divider_distance: 0.0
14+
reclass_distance_threshold: 0.1
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
/**:
2+
ros__parameters:
3+
global_slope_max_angle_deg: 10.0
4+
local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode
5+
split_points_distance_tolerance: 0.2
6+
use_virtual_ground_point: True
7+
split_height_distance: 0.2
8+
non_ground_height_threshold: 0.20
9+
grid_size_m: 0.1
10+
grid_mode_switch_radius: 20.0
11+
gnd_grid_buffer_size: 4
12+
detection_range_z_max: 2.5
13+
elevation_grid_mode: true
14+
low_priority_region_x: -20.0
15+
center_pcl_shift: 0.0
16+
radial_divider_angle_deg: 1.0
17+
use_recheck_ground_cluster: true
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<arg name="ground_segmentation_param_file" default="$(find-pkg-share ground_segmentation)/config/ransac_ground_filter.param.yaml"/>
4+
<arg name="input/pointcloud" default="/sensing/lidar/concatenated/pointcloud"/>
5+
<arg name="output/pointcloud" default="/perception/obstacle_segmentation/pointcloud"/>
6+
<node pkg="ground_segmentation" exec="ransac_ground_filter_node" name="ransac_ground_filter_node" output="screen">
7+
<remap from="input" to="$(var input/pointcloud)"/>
8+
<remap from="output" to="$(var output/pointcloud)"/>
9+
<param from="$(var ground_segmentation_param_file)"/>
10+
</node>
11+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<arg name="ground_segmentation_param_file" default="$(find-pkg-share ground_segmentation)/config/ray_ground_filter.param.yaml"/>
4+
<arg name="input/pointcloud" default="/sensing/lidar/concatenated/pointcloud"/>
5+
<arg name="output/pointcloud" default="/perception/obstacle_segmentation/pointcloud"/>
6+
<node pkg="ground_segmentation" exec="ray_ground_filter_node" name="ray_ground_filter_node" output="screen">
7+
<remap from="input" to="$(var input/pointcloud)"/>
8+
<remap from="output" to="$(var output/pointcloud)"/>
9+
<param from="$(var ground_segmentation_param_file)"/>
10+
</node>
11+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<arg name="ground_segmentation_param_file" default="$(find-pkg-share ground_segmentation)/config/scan_ground_filter.param.yaml"/>
4+
5+
<!-- vehicle info -->
6+
<arg name="vehicle_info_param_file" default="$(find-pkg-share vehicle_info_util)/config/vehicle_info.param.yaml"/>
7+
<arg name="input/pointcloud" default="/sensing/lidar/concatenated/pointcloud"/>
8+
<arg name="output/pointcloud" default="/perception/obstacle_segmentation/pointcloud"/>
9+
<node pkg="ground_segmentation" exec="scan_ground_filter_node" name="scan_ground_filter_node" output="screen">
10+
<remap from="input" to="$(var input/pointcloud)"/>
11+
<remap from="output" to="$(var output/pointcloud)"/>
12+
<param from="$(var ground_segmentation_param_file)"/>
13+
<param from="$(var vehicle_info_param_file)"/>
14+
</node>
15+
</launch>

perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -85,18 +85,18 @@ using pointcloud_preprocessor::get_param;
8585
RANSACGroundFilterComponent::RANSACGroundFilterComponent(const rclcpp::NodeOptions & options)
8686
: Filter("RANSACGroundFilter", options)
8787
{
88-
base_frame_ = declare_parameter("base_frame", "base_link");
89-
unit_axis_ = declare_parameter("unit_axis", "z");
90-
max_iterations_ = declare_parameter("max_iterations", 1000);
91-
min_inliers_ = declare_parameter("min_trial", 5000);
92-
min_points_ = declare_parameter("min_points", 1000);
93-
outlier_threshold_ = declare_parameter("outlier_threshold", 0.01);
94-
plane_slope_threshold_ = declare_parameter("plane_slope_threshold", 10.0);
95-
voxel_size_x_ = declare_parameter("voxel_size_x", 0.04);
96-
voxel_size_y_ = declare_parameter("voxel_size_y", 0.04);
97-
voxel_size_z_ = declare_parameter("voxel_size_z", 0.04);
98-
height_threshold_ = declare_parameter("height_threshold", 0.01);
99-
debug_ = declare_parameter("debug", false);
88+
base_frame_ = declare_parameter<std::string>("base_frame", "base_link");
89+
unit_axis_ = declare_parameter<std::string>("unit_axis");
90+
max_iterations_ = declare_parameter<int>("max_iterations");
91+
min_inliers_ = declare_parameter<int>("min_trial");
92+
min_points_ = declare_parameter<int>("min_points");
93+
outlier_threshold_ = declare_parameter<double>("outlier_threshold");
94+
plane_slope_threshold_ = declare_parameter<double>("plane_slope_threshold");
95+
voxel_size_x_ = declare_parameter<double>("voxel_size_x");
96+
voxel_size_y_ = declare_parameter<double>("voxel_size_y");
97+
voxel_size_z_ = declare_parameter<double>("voxel_size_z");
98+
height_threshold_ = declare_parameter<double>("height_threshold");
99+
debug_ = declare_parameter<bool>("debug");
100100

101101
if (unit_axis_ == "x") {
102102
unit_vec_ = Eigen::Vector3d::UnitX();

perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp

+12-12
Original file line numberDiff line numberDiff line change
@@ -48,22 +48,22 @@ RayGroundFilterComponent::RayGroundFilterComponent(const rclcpp::NodeOptions & o
4848
grid_precision_ = 0.2;
4949
ray_ground_filter::generateColors(colors_, color_num_);
5050

51-
min_x_ = declare_parameter("min_x", -0.01);
52-
max_x_ = declare_parameter("max_x", 0.01);
53-
min_y_ = declare_parameter("min_y", -0.01);
54-
max_y_ = declare_parameter("max_y", 0.01);
51+
min_x_ = declare_parameter<double>("min_x");
52+
max_x_ = declare_parameter<double>("max_x");
53+
min_y_ = declare_parameter<double>("min_y");
54+
max_y_ = declare_parameter<double>("max_y");
5555

5656
setVehicleFootprint(min_x_, max_x_, min_y_, max_y_);
5757

58-
use_vehicle_footprint_ = declare_parameter("use_vehicle_footprint", false);
58+
use_vehicle_footprint_ = declare_parameter<bool>("use_vehicle_footprint", false);
5959

60-
general_max_slope_ = declare_parameter("general_max_slope", 8.0);
61-
local_max_slope_ = declare_parameter("local_max_slope", 6.0);
62-
initial_max_slope_ = declare_parameter("initial_max_slope", 3.0);
63-
radial_divider_angle_ = declare_parameter("radial_divider_angle", 1.0);
64-
min_height_threshold_ = declare_parameter("min_height_threshold", 0.15);
65-
concentric_divider_distance_ = declare_parameter("concentric_divider_distance", 0.0);
66-
reclass_distance_threshold_ = declare_parameter("reclass_distance_threshold", 0.1);
60+
general_max_slope_ = declare_parameter<double>("general_max_slope");
61+
local_max_slope_ = declare_parameter<double>("local_max_slope");
62+
initial_max_slope_ = declare_parameter<double>("initial_max_slope");
63+
radial_divider_angle_ = declare_parameter<double>("radial_divider_angle");
64+
min_height_threshold_ = declare_parameter<double>("min_height_threshold");
65+
concentric_divider_distance_ = declare_parameter<double>("concentric_divider_distance");
66+
reclass_distance_threshold_ = declare_parameter<double>("reclass_distance_threshold");
6767
}
6868

6969
using std::placeholders::_1;

perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp

+16-18
Original file line numberDiff line numberDiff line change
@@ -37,24 +37,22 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
3737
{
3838
// set initial parameters
3939
{
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");
5856
radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_);
5957
vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo();
6058

perception/ground_segmentation/test/test_ray_ground_filter.cpp

+35-5
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
3030
#include <tf2_sensor_msgs/tf2_sensor_msgs.hpp>
3131
#endif
32-
32+
#include <yaml-cpp/yaml.h>
3333
class RayGroundFilterComponentTestSuite : public ::testing::Test
3434
{
3535
protected:
@@ -63,8 +63,25 @@ class RayGroundFilterComponentTest : public ground_segmentation::RayGroundFilter
6363

6464
TEST_F(RayGroundFilterComponentTestSuite, TestCase1)
6565
{
66-
// read pcd to pointcloud
6766
const auto share_dir = ament_index_cpp::get_package_share_directory("ground_segmentation");
67+
const auto config_path = share_dir + "/config/ray_ground_filter.param.yaml";
68+
// std::cout << "config_path:" << config_path << std::endl;
69+
YAML::Node config = YAML::LoadFile(config_path);
70+
auto params = config["/**"]["ros__parameters"];
71+
72+
double min_x_ = params["min_x"].as<float>();
73+
double max_x_ = params["max_x"].as<float>();
74+
double min_y_ = params["min_y"].as<float>();
75+
double max_y_ = params["max_y"].as<float>();
76+
bool use_vehicle_footprint_ = params["use_vehicle_footprint"].as<bool>();
77+
double general_max_slope_ = params["general_max_slope"].as<float>();
78+
double local_max_slope_ = params["local_max_slope"].as<float>();
79+
double initial_max_slope_ = params["initial_max_slope"].as<float>();
80+
double radial_divider_angle_ = params["radial_divider_angle"].as<float>();
81+
double min_height_threshold_ = params["min_height_threshold"].as<float>();
82+
double concentric_divider_distance_ = params["concentric_divider_distance"].as<float>();
83+
double reclass_distance_threshold_ = params["reclass_distance_threshold"].as<float>();
84+
6885
const auto pcd_path = share_dir + "/data/test.pcd";
6986
pcl::PointCloud<pcl::PointXYZ> cloud;
7087
pcl::io::loadPCDFile<pcl::PointXYZ>(pcd_path, cloud);
@@ -94,10 +111,23 @@ TEST_F(RayGroundFilterComponentTestSuite, TestCase1)
94111

95112
rclcpp::NodeOptions node_options;
96113
std::vector<rclcpp::Parameter> parameters;
114+
97115
parameters.emplace_back(rclcpp::Parameter("base_frame", "base_link"));
98-
parameters.emplace_back(rclcpp::Parameter("general_max_slope", 2.0));
99-
parameters.emplace_back(rclcpp::Parameter("local_max_slope", 3.0));
100-
parameters.emplace_back(rclcpp::Parameter("initial_max_slope", 1.0));
116+
parameters.emplace_back(rclcpp::Parameter("general_max_slope", general_max_slope_));
117+
parameters.emplace_back(rclcpp::Parameter("local_max_slope", local_max_slope_));
118+
parameters.emplace_back(rclcpp::Parameter("initial_max_slope", initial_max_slope_));
119+
parameters.emplace_back(rclcpp::Parameter("radial_divider_angle", radial_divider_angle_));
120+
parameters.emplace_back(rclcpp::Parameter("min_height_threshold", min_height_threshold_));
121+
parameters.emplace_back(
122+
rclcpp::Parameter("concentric_divider_distance", concentric_divider_distance_));
123+
parameters.emplace_back(
124+
rclcpp::Parameter("reclass_distance_threshold", reclass_distance_threshold_));
125+
parameters.emplace_back(rclcpp::Parameter("min_x", min_x_));
126+
parameters.emplace_back(rclcpp::Parameter("max_x", max_x_));
127+
parameters.emplace_back(rclcpp::Parameter("min_y", min_y_));
128+
parameters.emplace_back(rclcpp::Parameter("max_y", max_y_));
129+
parameters.emplace_back(rclcpp::Parameter("use_vehicle_footprint", use_vehicle_footprint_));
130+
101131
node_options.parameter_overrides(parameters);
102132
auto ray_ground_filter_test = std::make_shared<RayGroundFilterComponentTest>(node_options);
103133
ray_ground_filter_test->input_pointcloud_pub_->publish(*input_msg_ptr);

perception/ground_segmentation/test/test_scan_ground_filter.cpp

+38-25
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ class ScanGroundFilterTest : public ::testing::Test
3838
{
3939
rclcpp::init(0, nullptr);
4040

41+
parse_yaml();
42+
4143
dummy_node_ = std::make_shared<rclcpp::Node>("ScanGroundFilterTest");
4244
input_pointcloud_pub_ = rclcpp::create_publisher<sensor_msgs::msg::PointCloud2>(
4345
dummy_node_, "/test_scan_ground_filter/input_cloud", 1);
@@ -58,6 +60,30 @@ class ScanGroundFilterTest : public ::testing::Test
5860
parameters.emplace_back(rclcpp::Parameter("right_overhang", 0.1));
5961
parameters.emplace_back(rclcpp::Parameter("vehicle_height", 2.5));
6062
parameters.emplace_back(rclcpp::Parameter("max_steer_angle", 0.7));
63+
64+
parameters.emplace_back(
65+
rclcpp::Parameter("global_slope_max_angle_deg", global_slope_max_angle_deg_));
66+
parameters.emplace_back(
67+
rclcpp::Parameter("local_slope_max_angle_deg", local_slope_max_angle_deg_));
68+
parameters.emplace_back(
69+
rclcpp::Parameter("split_points_distance_tolerance", split_points_distance_tolerance_));
70+
parameters.emplace_back(
71+
rclcpp::Parameter("use_virtual_ground_point", use_virtual_ground_point_));
72+
parameters.emplace_back(rclcpp::Parameter("split_height_distance", split_height_distance_));
73+
parameters.emplace_back(
74+
rclcpp::Parameter("non_ground_height_threshold", non_ground_height_threshold_));
75+
parameters.emplace_back(rclcpp::Parameter("grid_size_m", grid_size_m_));
76+
parameters.emplace_back(rclcpp::Parameter("grid_mode_switch_radius", grid_mode_switch_radius_));
77+
parameters.emplace_back(rclcpp::Parameter("gnd_grid_buffer_size", gnd_grid_buffer_size_));
78+
parameters.emplace_back(rclcpp::Parameter("detection_range_z_max", detection_range_z_max_));
79+
parameters.emplace_back(rclcpp::Parameter("elevation_grid_mode", elevation_grid_mode_));
80+
parameters.emplace_back(rclcpp::Parameter("low_priority_region_x", low_priority_region_x_));
81+
parameters.emplace_back(rclcpp::Parameter("center_pcl_shift", center_pcl_shift_));
82+
parameters.emplace_back(
83+
rclcpp::Parameter("radial_divider_angle_deg", radial_divider_angle_deg_));
84+
parameters.emplace_back(
85+
rclcpp::Parameter("use_recheck_ground_cluster", use_recheck_ground_cluster_));
86+
6187
options.parameter_overrides(parameters);
6288

6389
scan_ground_filter_ = std::make_shared<ground_segmentation::ScanGroundFilterComponent>(options);
@@ -88,8 +114,6 @@ class ScanGroundFilterTest : public ::testing::Test
88114
t.transform.rotation.w = q.w();
89115

90116
tf2::doTransform(*origin_input_msg_ptr, *input_msg_ptr_, t);
91-
92-
parse_yaml();
93117
}
94118

95119
ScanGroundFilterTest() {}
@@ -113,10 +137,10 @@ class ScanGroundFilterTest : public ::testing::Test
113137
void parse_yaml()
114138
{
115139
const auto share_dir = ament_index_cpp::get_package_share_directory("ground_segmentation");
116-
const auto config_path = share_dir + "/config/ground_segmentation.param.yaml";
140+
const auto config_path = share_dir + "/config/scan_ground_filter.param.yaml";
117141
// std::cout << "config_path:" << config_path << std::endl;
118142
YAML::Node config = YAML::LoadFile(config_path);
119-
auto params = config["/**"]["ros__parameters"]["common_ground_filter"]["parameters"];
143+
auto params = config["/**"]["ros__parameters"];
120144
global_slope_max_angle_deg_ = params["global_slope_max_angle_deg"].as<float>();
121145
local_slope_max_angle_deg_ = params["local_slope_max_angle_deg"].as<float>();
122146
split_points_distance_tolerance_ = params["split_points_distance_tolerance"].as<float>();
@@ -127,6 +151,11 @@ class ScanGroundFilterTest : public ::testing::Test
127151
gnd_grid_buffer_size_ = params["gnd_grid_buffer_size"].as<uint16_t>();
128152
detection_range_z_max_ = params["detection_range_z_max"].as<float>();
129153
elevation_grid_mode_ = params["elevation_grid_mode"].as<bool>();
154+
low_priority_region_x_ = params["low_priority_region_x"].as<float>();
155+
use_virtual_ground_point_ = params["use_virtual_ground_point"].as<bool>();
156+
center_pcl_shift_ = params["center_pcl_shift"].as<float>();
157+
radial_divider_angle_deg_ = params["radial_divider_angle_deg"].as<float>();
158+
use_recheck_ground_cluster_ = params["use_recheck_ground_cluster"].as<bool>();
130159
}
131160

132161
float global_slope_max_angle_deg_ = 0.0;
@@ -139,34 +168,18 @@ class ScanGroundFilterTest : public ::testing::Test
139168
uint16_t gnd_grid_buffer_size_ = 0;
140169
float detection_range_z_max_ = 0.0;
141170
bool elevation_grid_mode_ = false;
171+
float low_priority_region_x_ = 0.0;
172+
bool use_virtual_ground_point_;
173+
float center_pcl_shift_;
174+
float radial_divider_angle_deg_;
175+
bool use_recheck_ground_cluster_;
142176
};
143177

144178
TEST_F(ScanGroundFilterTest, TestCase1)
145179
{
146180
input_pointcloud_pub_->publish(*input_msg_ptr_);
147181
sensor_msgs::msg::PointCloud2 out_cloud;
148182

149-
// set filter parameter
150-
scan_ground_filter_->set_parameter(
151-
rclcpp::Parameter("global_slope_max_angle_deg", global_slope_max_angle_deg_));
152-
scan_ground_filter_->set_parameter(
153-
rclcpp::Parameter("local_slope_max_angle_deg", local_slope_max_angle_deg_));
154-
scan_ground_filter_->set_parameter(
155-
rclcpp::Parameter("split_points_distance_tolerance", split_points_distance_tolerance_));
156-
scan_ground_filter_->set_parameter(
157-
rclcpp::Parameter("split_height_distance", split_height_distance_));
158-
scan_ground_filter_->set_parameter(
159-
rclcpp::Parameter("non_ground_height_threshold", non_ground_height_threshold_));
160-
scan_ground_filter_->set_parameter(rclcpp::Parameter("grid_size_m", grid_size_m_));
161-
scan_ground_filter_->set_parameter(
162-
rclcpp::Parameter("grid_mode_switch_radius", grid_mode_switch_radius_));
163-
scan_ground_filter_->set_parameter(
164-
rclcpp::Parameter("gnd_grid_buffer_size", gnd_grid_buffer_size_));
165-
scan_ground_filter_->set_parameter(
166-
rclcpp::Parameter("detection_range_z_max", detection_range_z_max_));
167-
scan_ground_filter_->set_parameter(
168-
rclcpp::Parameter("elevation_grid_mode", elevation_grid_mode_));
169-
170183
filter(out_cloud);
171184
output_pointcloud_pub_->publish(out_cloud);
172185

0 commit comments

Comments
 (0)