Skip to content

Commit 62866bc

Browse files
committed
relative filters
1 parent 92d84b2 commit 62866bc

File tree

1 file changed

+7
-13
lines changed

1 file changed

+7
-13
lines changed

spatio_temporal_voxel_layer/src/spatio_temporal_voxel_layer.cpp

Lines changed: 7 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -245,28 +245,22 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
245245
node->get_parameter(name_ + "." + source + "." + "model_type", model_type_int);
246246
ModelType model_type = static_cast<ModelType>(model_type_int);
247247

248-
switch (filter)
249-
{
250-
case "passthrough":
248+
249+
if (filter_str == "passthrough") {
251250
RCLCPP_INFO(logger_, "Passthough filter activated.");
252251
filter = buffer::Filters::PASSTHROUGH;
253-
break;
254-
case "voxel":
252+
} else if (filter_str == "voxel") {
255253
RCLCPP_INFO(logger_, "Voxel filter activated.");
256254
filter = buffer::Filters::VOXEL;
257-
break;
258-
case "passthrough_relative":
255+
} else if (filter_str == "passthrough_relative") {
259256
RCLCPP_INFO(logger_, "Relative Passthough filter activated.");
260257
filter = buffer::Filters::PASSTHROUGH_RELATIVE;
261-
break;
262-
case "voxel_relative":
258+
} else if (filter_str == "voxel_relative") {
263259
RCLCPP_INFO(logger_, "Relative Voxel filter activated.");
264260
filter = buffer::Filters::VOXEL_RELATIVE;
265-
break;
266-
default:
261+
} else {
267262
RCLCPP_INFO(logger_, "No filters activated.");
268263
filter = buffer::Filters::NONE;
269-
break;
270264
}
271265

272266
if (!(data_type == "PointCloud2" || data_type == "LaserScan")) {
@@ -280,7 +274,7 @@ void SpatioTemporalVoxelLayer::onInitialize(void)
280274
new buffer::MeasurementBuffer(
281275
source, topic,
282276
observation_keep_time, expected_update_rate, min_obstacle_height,
283-
max_obstacle_height, obstacle_range, *tf_, _global_frame, sensor_frame,
277+
max_obstacle_height, obstacle_range, *tf_, _global_frame, sensor_frame, z_reference_frame,
284278
transform_tolerance, min_z, max_z, vFOV, vFOVPadding, hFOV,
285279
decay_acceleration, marking, clearing, _voxel_size,
286280
filter, voxel_min_points, enabled, clear_after_reading, model_type,

0 commit comments

Comments
 (0)