Skip to content

Commit da4320d

Browse files
scepter914StepTurtle
authored andcommitted
fix(radar_threshold_filter): delete default param in src (autowarefoundation#6308)
Signed-off-by: scepter914 <scepter914@gmail.com>
1 parent 10a8200 commit da4320d

File tree

1 file changed

+12
-13
lines changed

1 file changed

+12
-13
lines changed

sensing/radar_threshold_filter/src/radar_threshold_filter_node/radar_threshold_filter_node.cpp

+12-13
Original file line numberDiff line numberDiff line change
@@ -64,19 +64,18 @@ RadarThresholdFilterNode::RadarThresholdFilterNode(const rclcpp::NodeOptions & n
6464
std::bind(&RadarThresholdFilterNode::onSetParam, this, _1));
6565

6666
// Node Parameter
67-
node_param_.is_amplitude_filter =
68-
declare_parameter<bool>("node_params.is_amplitude_filter", false);
69-
node_param_.amplitude_min = declare_parameter<double>("node_params.amplitude_min", 0.0);
70-
node_param_.amplitude_max = declare_parameter<double>("node_params.amplitude_max", 0.0);
71-
node_param_.is_range_filter = declare_parameter<bool>("node_params.is_range_filter", false);
72-
node_param_.range_min = declare_parameter<double>("node_params.range_min", 0.0);
73-
node_param_.range_max = declare_parameter<double>("node_params.range_max", 0.0);
74-
node_param_.is_azimuth_filter = declare_parameter<bool>("node_params.is_azimuth_filter", false);
75-
node_param_.azimuth_min = declare_parameter<double>("node_params.azimuth_min", 0.0);
76-
node_param_.azimuth_max = declare_parameter<double>("node_params.azimuth_max", 0.0);
77-
node_param_.is_z_filter = declare_parameter<bool>("node_params.is_z_filter", false);
78-
node_param_.z_min = declare_parameter<double>("node_params.z_min", 0.0);
79-
node_param_.z_max = declare_parameter<double>("node_params.z_max", 0.0);
67+
node_param_.is_amplitude_filter = declare_parameter<bool>("node_params.is_amplitude_filter");
68+
node_param_.amplitude_min = declare_parameter<double>("node_params.amplitude_min");
69+
node_param_.amplitude_max = declare_parameter<double>("node_params.amplitude_max");
70+
node_param_.is_range_filter = declare_parameter<bool>("node_params.is_range_filter");
71+
node_param_.range_min = declare_parameter<double>("node_params.range_min");
72+
node_param_.range_max = declare_parameter<double>("node_params.range_max");
73+
node_param_.is_azimuth_filter = declare_parameter<bool>("node_params.is_azimuth_filter");
74+
node_param_.azimuth_min = declare_parameter<double>("node_params.azimuth_min");
75+
node_param_.azimuth_max = declare_parameter<double>("node_params.azimuth_max");
76+
node_param_.is_z_filter = declare_parameter<bool>("node_params.is_z_filter");
77+
node_param_.z_min = declare_parameter<double>("node_params.z_min");
78+
node_param_.z_max = declare_parameter<double>("node_params.z_max");
8079

8180
// Subscriber
8281
sub_radar_ = create_subscription<RadarScan>(

0 commit comments

Comments
 (0)