|
1 |
| -// Copyright 2020 Tier IV, Inc. |
| 1 | +// Copyright 2024 TIER IV, Inc. |
2 | 2 | //
|
3 | 3 | // Licensed under the Apache License, Version 2.0 (the "License");
|
4 | 4 | // you may not use this file except in compliance with the License.
|
|
12 | 12 | // See the License for the specific language governing permissions and
|
13 | 13 | // limitations under the License.
|
14 | 14 |
|
15 |
| -#include "autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp" |
| 15 | +#include "autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp" |
16 | 16 |
|
17 | 17 | #include "autoware_point_types/types.hpp"
|
18 | 18 |
|
@@ -47,22 +47,21 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
|
47 | 47 |
|
48 | 48 | // set initial parameters
|
49 | 49 | {
|
50 |
| - distance_ratio_ = static_cast<double>(declare_parameter("distance_ratio", 1.03)); |
51 |
| - object_length_threshold_ = |
52 |
| - static_cast<double>(declare_parameter("object_length_threshold", 0.1)); |
53 |
| - num_points_threshold_ = static_cast<int>(declare_parameter("num_points_threshold", 4)); |
54 |
| - max_rings_num_ = static_cast<uint16_t>(declare_parameter("max_rings_num", 128)); |
| 50 | + distance_ratio_ = declare_parameter<double>("distance_ratio"); |
| 51 | + object_length_threshold_ = declare_parameter<double>("object_length_threshold"); |
| 52 | + num_points_threshold_ = declare_parameter<int>("num_points_threshold"); |
| 53 | + max_rings_num_ = static_cast<uint16_t>(declare_parameter<int64_t>("max_rings_num")); |
55 | 54 | max_points_num_per_ring_ =
|
56 |
| - static_cast<size_t>(declare_parameter("max_points_num_per_ring", 4000)); |
57 |
| - publish_outlier_pointcloud_ = |
58 |
| - static_cast<bool>(declare_parameter("publish_outlier_pointcloud", false)); |
59 |
| - |
60 |
| - min_azimuth_deg_ = static_cast<float>(declare_parameter("min_azimuth_deg", 0.0)); |
61 |
| - max_azimuth_deg_ = static_cast<float>(declare_parameter("max_azimuth_deg", 360.0)); |
62 |
| - max_distance_ = static_cast<float>(declare_parameter("max_distance", 12.0)); |
63 |
| - vertical_bins_ = static_cast<int>(declare_parameter("vertical_bins", 128)); |
64 |
| - horizontal_bins_ = static_cast<int>(declare_parameter("horizontal_bins", 36)); |
65 |
| - noise_threshold_ = static_cast<int>(declare_parameter("noise_threshold", 2)); |
| 55 | + static_cast<size_t>(declare_parameter<int64_t>("max_points_num_per_ring")); |
| 56 | + |
| 57 | + publish_outlier_pointcloud_ = declare_parameter<bool>("publish_outlier_pointcloud"); |
| 58 | + |
| 59 | + min_azimuth_deg_ = declare_parameter<float>("min_azimuth_deg"); |
| 60 | + max_azimuth_deg_ = declare_parameter<float>("max_azimuth_deg"); |
| 61 | + max_distance_ = declare_parameter<float>("max_distance"); |
| 62 | + vertical_bins_ = declare_parameter<int>("vertical_bins"); |
| 63 | + horizontal_bins_ = declare_parameter<int>("horizontal_bins"); |
| 64 | + noise_threshold_ = declare_parameter<int>("noise_threshold"); |
66 | 65 | }
|
67 | 66 |
|
68 | 67 | using std::placeholders::_1;
|
|
0 commit comments