Skip to content

Commit cf1177c

Browse files
change from publish_noise_points to publish_outlier_pointcloud
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 5743ba7 commit cf1177c

File tree

3 files changed

+18
-16
lines changed

3 files changed

+18
-16
lines changed

sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md

+8-8
Original file line numberDiff line numberDiff line change
@@ -22,14 +22,14 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref
2222

2323
### Core Parameters
2424

25-
| Name | Type | Default Value | Description |
26-
| ------------------------- | ------- | ------------- | ------------------------------------------------------------------------------------------------------- |
27-
| `distance_ratio` | double | 1.03 | |
28-
| `object_length_threshold` | double | 0.1 | |
29-
| `num_points_threshold` | int | 4 | |
30-
| `max_rings_num` | uint_16 | 128 | |
31-
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
32-
| `publish_noise_points` | bool | false | Flag to publish point cloud noise. Due to performance concerns, please set to false during experiments. |
25+
| Name | Type | Default Value | Description |
26+
| ---------------------------- | ------- | ------------- | ------------------------------------------------------------------------------------------------------- |
27+
| `distance_ratio` | double | 1.03 | |
28+
| `object_length_threshold` | double | 0.1 | |
29+
| `num_points_threshold` | int | 4 | |
30+
| `max_rings_num` | uint_16 | 128 | |
31+
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
32+
| `publish_outlier_pointcloud` | bool | false | Flag to publish point cloud noise. Due to performance concerns, please set to false during experiments. |
3333

3434
## Assumptions / Known limits
3535

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
5151
int num_points_threshold_;
5252
uint16_t max_rings_num_;
5353
size_t max_points_num_per_ring_;
54-
bool publish_noise_points_;
54+
bool publish_outlier_pointcloud_;
5555

5656
/** \brief Parameter service callback result : needed to be hold */
5757
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

+9-7
Original file line numberDiff line numberDiff line change
@@ -47,7 +47,8 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
4747
max_rings_num_ = static_cast<uint16_t>(declare_parameter("max_rings_num", 128));
4848
max_points_num_per_ring_ =
4949
static_cast<size_t>(declare_parameter("max_points_num_per_ring", 4000));
50-
publish_noise_points_ = static_cast<bool>(declare_parameter("publish_noise_points", false));
50+
publish_outlier_pointcloud_ =
51+
static_cast<bool>(declare_parameter("publish_outlier_pointcloud", false));
5152
}
5253

5354
using std::placeholders::_1;
@@ -74,7 +75,7 @@ void RingOutlierFilterComponent::faster_filter(
7475
// Set up the noise points cloud, if noise points are to be published.
7576
PointCloud2 noise_points;
7677
size_t noise_points_size = 0;
77-
if (publish_noise_points_) {
78+
if (publish_outlier_pointcloud_) {
7879
noise_points.point_step = sizeof(PointXYZI);
7980
noise_points.data.resize(noise_points.point_step * input->width);
8081
}
@@ -159,7 +160,7 @@ void RingOutlierFilterComponent::faster_filter(
159160

160161
output_size += output.point_step;
161162
}
162-
} else if (publish_noise_points_) {
163+
} else if (publish_outlier_pointcloud_) {
163164
for (int i = walk_first_idx; i <= walk_last_idx; i++) {
164165
auto noise_ptr = reinterpret_cast<PointXYZI *>(&noise_points.data[noise_points_size]);
165166
auto input_ptr =
@@ -208,7 +209,7 @@ void RingOutlierFilterComponent::faster_filter(
208209

209210
output_size += output.point_step;
210211
}
211-
} else if (publish_noise_points_) {
212+
} else if (publish_outlier_pointcloud_) {
212213
for (int i = walk_first_idx; i < walk_last_idx; i++) {
213214
auto noise_ptr = reinterpret_cast<PointXYZI *>(&noise_points.data[noise_points_size]);
214215
auto input_ptr = reinterpret_cast<const PointXYZI *>(&input->data[indices[i]]);
@@ -231,7 +232,7 @@ void RingOutlierFilterComponent::faster_filter(
231232

232233
setUpPointCloudFormat(input, output, output_size, /*num_fields=*/4);
233234

234-
if (publish_noise_points_) {
235+
if (publish_outlier_pointcloud_) {
235236
setUpPointCloudFormat(input, noise_points, noise_points_size, /*num_fields=*/4);
236237
noise_points_publisher_->publish(noise_points);
237238
}
@@ -281,8 +282,9 @@ rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallba
281282
if (get_param(p, "num_points_threshold", num_points_threshold_)) {
282283
RCLCPP_DEBUG(get_logger(), "Setting new num_points_threshold to: %d.", num_points_threshold_);
283284
}
284-
if (get_param(p, "publish_noise_points", publish_noise_points_)) {
285-
RCLCPP_DEBUG(get_logger(), "Setting new publish_noise_points to: %d.", publish_noise_points_);
285+
if (get_param(p, "publish_outlier_pointcloud", publish_outlier_pointcloud_)) {
286+
RCLCPP_DEBUG(
287+
get_logger(), "Setting new publish_outlier_pointcloud to: %d.", publish_outlier_pointcloud_);
286288
}
287289

288290
rcl_interfaces::msg::SetParametersResult result;

0 commit comments

Comments
 (0)