@@ -38,6 +38,8 @@ class ScanGroundFilterTest : public ::testing::Test
38
38
{
39
39
rclcpp::init (0 , nullptr );
40
40
41
+ parse_yaml ();
42
+
41
43
dummy_node_ = std::make_shared<rclcpp::Node>(" ScanGroundFilterTest" );
42
44
input_pointcloud_pub_ = rclcpp::create_publisher<sensor_msgs::msg::PointCloud2>(
43
45
dummy_node_, " /test_scan_ground_filter/input_cloud" , 1 );
@@ -58,6 +60,30 @@ class ScanGroundFilterTest : public ::testing::Test
58
60
parameters.emplace_back (rclcpp::Parameter (" right_overhang" , 0.1 ));
59
61
parameters.emplace_back (rclcpp::Parameter (" vehicle_height" , 2.5 ));
60
62
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
+
61
87
options.parameter_overrides (parameters);
62
88
63
89
scan_ground_filter_ = std::make_shared<ground_segmentation::ScanGroundFilterComponent>(options);
@@ -88,8 +114,6 @@ class ScanGroundFilterTest : public ::testing::Test
88
114
t.transform .rotation .w = q.w ();
89
115
90
116
tf2::doTransform (*origin_input_msg_ptr, *input_msg_ptr_, t);
91
-
92
- parse_yaml ();
93
117
}
94
118
95
119
ScanGroundFilterTest () {}
@@ -113,10 +137,10 @@ class ScanGroundFilterTest : public ::testing::Test
113
137
void parse_yaml ()
114
138
{
115
139
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" ;
117
141
// std::cout << "config_path:" << config_path << std::endl;
118
142
YAML::Node config = YAML::LoadFile (config_path);
119
- auto params = config[" /**" ][" ros__parameters" ][ " common_ground_filter " ][ " parameters " ] ;
143
+ auto params = config[" /**" ][" ros__parameters" ];
120
144
global_slope_max_angle_deg_ = params[" global_slope_max_angle_deg" ].as <float >();
121
145
local_slope_max_angle_deg_ = params[" local_slope_max_angle_deg" ].as <float >();
122
146
split_points_distance_tolerance_ = params[" split_points_distance_tolerance" ].as <float >();
@@ -127,6 +151,11 @@ class ScanGroundFilterTest : public ::testing::Test
127
151
gnd_grid_buffer_size_ = params[" gnd_grid_buffer_size" ].as <uint16_t >();
128
152
detection_range_z_max_ = params[" detection_range_z_max" ].as <float >();
129
153
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 >();
130
159
}
131
160
132
161
float global_slope_max_angle_deg_ = 0.0 ;
@@ -139,34 +168,18 @@ class ScanGroundFilterTest : public ::testing::Test
139
168
uint16_t gnd_grid_buffer_size_ = 0 ;
140
169
float detection_range_z_max_ = 0.0 ;
141
170
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_;
142
176
};
143
177
144
178
TEST_F (ScanGroundFilterTest, TestCase1)
145
179
{
146
180
input_pointcloud_pub_->publish (*input_msg_ptr_);
147
181
sensor_msgs::msg::PointCloud2 out_cloud;
148
182
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
-
170
183
filter (out_cloud);
171
184
output_pointcloud_pub_->publish (out_cloud);
172
185
0 commit comments