From add258ee15db7fcc35f7ecb1b400b1a5b04ac3e2 Mon Sep 17 00:00:00 2001 From: scepter914 Date: Fri, 2 Feb 2024 17:02:52 +0900 Subject: [PATCH] fix(radar_crossing_objects_noise_filter): delete default param in src Signed-off-by: scepter914 --- .../radar_crossing_objects_noise_filter_node.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp b/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp index 947856e5d2a4d..5b69ba65f3964 100644 --- a/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp +++ b/perception/radar_crossing_objects_noise_filter/src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp @@ -64,8 +64,8 @@ RadarCrossingObjectsNoiseFilterNode::RadarCrossingObjectsNoiseFilterNode( std::bind(&RadarCrossingObjectsNoiseFilterNode::onSetParam, this, std::placeholders::_1)); // Node Parameter - node_param_.angle_threshold = declare_parameter("angle_threshold", 1.0472); - node_param_.velocity_threshold = declare_parameter("velocity_threshold", 3.0); + node_param_.angle_threshold = declare_parameter("angle_threshold"); + node_param_.velocity_threshold = declare_parameter("velocity_threshold"); // Subscriber sub_objects_ = create_subscription(