Skip to content

Commit d29adc7

Browse files
committed
Revert "fix(ground_segmentation): add field select option"
This reverts commit 36fc554.
1 parent d1328fd commit d29adc7

File tree

3 files changed

+2
-13
lines changed

3 files changed

+2
-13
lines changed

launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py

+1-6
Original file line numberDiff line numberDiff line change
@@ -118,10 +118,7 @@ def create_additional_pipeline(self, lidar_name):
118118
("output", f"{lidar_name}/pointcloud"),
119119
],
120120
parameters=[
121-
self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["parameters"],
122-
{"input_frame": "base_link"},
123-
{"output_frame": "base_link"},
124-
{"output_intensity_field": LaunchConfiguration("output_intensity_field")},
121+
self.ground_segmentation_param[f"{lidar_name}_ground_filter"]["parameters"]
125122
],
126123
extra_arguments=[
127124
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
@@ -271,7 +268,6 @@ def create_common_pipeline(self, input_topic, output_topic):
271268
self.vehicle_info,
272269
{"input_frame": "base_link"},
273270
{"output_frame": "base_link"},
274-
{"output_intensity_field": LaunchConfiguration("output_intensity_field")},
275271
],
276272
extra_arguments=[
277273
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
@@ -562,7 +558,6 @@ def add_launch_arg(name: str, default_value=None):
562558
add_launch_arg("pointcloud_container_name", "pointcloud_container")
563559
add_launch_arg("individual_container_name", "ground_segmentation_container")
564560
add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud")
565-
add_launch_arg("output_intensity_field", "False")
566561

567562
set_container_executable = SetLaunchConfiguration(
568563
"container_executable",

perception/ground_segmentation/include/ground_segmentation/scan_ground_filter_nodelet.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -196,7 +196,6 @@ class ScanGroundFilterComponent : public pointcloud_preprocessor::Filter
196196
bool use_recheck_ground_cluster_; // to enable recheck ground cluster
197197
bool use_lowest_point_; // to select lowest point for reference in recheck ground cluster,
198198
// otherwise select middle point
199-
int output_field_num_{3};
200199
size_t radial_dividers_num_;
201200
VehicleInfo vehicle_info_;
202201

perception/ground_segmentation/src/scan_ground_filter_nodelet.cpp

+1-6
Original file line numberDiff line numberDiff line change
@@ -58,11 +58,6 @@ ScanGroundFilterComponent::ScanGroundFilterComponent(const rclcpp::NodeOptions &
5858
use_virtual_ground_point_ = declare_parameter<bool>("use_virtual_ground_point");
5959
use_recheck_ground_cluster_ = declare_parameter<bool>("use_recheck_ground_cluster");
6060
use_lowest_point_ = declare_parameter<bool>("use_lowest_point");
61-
if (declare_parameter<bool>("output_intensity_field")) {
62-
output_field_num_ = 4;
63-
} else {
64-
output_field_num_ = 3;
65-
}
6661
radial_dividers_num_ = std::ceil(2.0 * M_PI / radial_divider_angle_rad_);
6762
vehicle_info_ = VehicleInfoUtil(*this).getVehicleInfo();
6863

@@ -615,7 +610,7 @@ void ScanGroundFilterComponent::faster_filter(
615610
output.row_step = no_ground_indices.indices.size() * input->point_step;
616611
output.data.resize(output.row_step);
617612
output.width = no_ground_indices.indices.size();
618-
output.fields.assign(input->fields.begin(), input->fields.begin() + output_field_num_);
613+
output.fields.assign(input->fields.begin(), input->fields.begin() + 4);
619614
output.is_dense = true;
620615
output.height = input->height;
621616
output.is_bigendian = input->is_bigendian;

0 commit comments

Comments
 (0)