Skip to content

Commit

Permalink
Merge pull request #1849 from tier4/sync-awf-latest
Browse files Browse the repository at this point in the history
chore: sync awf-latest
  • Loading branch information
tier4-autoware-public-bot[bot] authored Feb 19, 2025
2 parents 505f97e + b795851 commit 78e9c7e
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<arg name="pedestrian_traffic_light_classifier_label_name" default="lamp_labels_ped.txt" description="classifier label filename"/>
<arg name="car_traffic_light_classifier_model_name" default="traffic_light_classifier_mobilenetv2_batch_6.onnx" description="classifier onnx model filename"/>
<arg name="pedestrian_traffic_light_classifier_model_name" default="ped_traffic_light_classifier_mobilenetv2_batch_6.onnx" description="classifier onnx model filename"/>
<arg name="traffic_light_multi_camera_fusion_param_path" default="$(find-pkg-share autoware_traffic_light_multi_camera_fusion)/config/traffic_light_multi_camera_fusion.param.yaml"/>

<!-- main TLR pipeline on each camera -->
<group unless="$(var fusion_only)">
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,5 @@
is_z_filter: false
z_min: -2.0
z_max: 5.0

max_queue_size: 5
Original file line number Diff line number Diff line change
Expand Up @@ -75,13 +75,16 @@ RadarThresholdFilterNode::RadarThresholdFilterNode(const rclcpp::NodeOptions & n
node_param_.is_z_filter = declare_parameter<bool>("node_params.is_z_filter");
node_param_.z_min = declare_parameter<double>("node_params.z_min");
node_param_.z_max = declare_parameter<double>("node_params.z_max");
node_param_.max_queue_size = declare_parameter<int64_t>("node_params.max_queue_size");

// Subscriber
sub_radar_ = create_subscription<RadarScan>(
"~/input/radar", rclcpp::QoS{1}, std::bind(&RadarThresholdFilterNode::onData, this, _1));
"~/input/radar", rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size),
std::bind(&RadarThresholdFilterNode::onData, this, _1));

// Publisher
pub_radar_ = create_publisher<RadarScan>("~/output/radar", 1);
pub_radar_ = create_publisher<RadarScan>(
"~/output/radar", rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size));
}

rcl_interfaces::msg::SetParametersResult RadarThresholdFilterNode::onSetParam(
Expand All @@ -103,6 +106,7 @@ rcl_interfaces::msg::SetParametersResult RadarThresholdFilterNode::onSetParam(
update_param(params, "node_params.is_z_filter", p.is_z_filter);
update_param(params, "node_params.z_min", p.z_min);
update_param(params, "node_params.z_max", p.z_max);
update_param(params, "node_params.max_queue_size", p.max_queue_size);
}
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
result.successful = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ class RadarThresholdFilterNode : public rclcpp::Node
bool is_z_filter{};
double z_min{};
double z_max{};
size_t max_queue_size{};
};

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ TEST(RadarThresholdFilter, isWithinThreshold)
const double azimuth_max = 1.2;
const double z_min = -2.0;
const double z_max = 5.0;
const int64_t max_queue_size = 5;
// amplitude filter
{
rclcpp::NodeOptions node_options;
Expand All @@ -48,6 +49,7 @@ TEST(RadarThresholdFilter, isWithinThreshold)
{"node_params.is_z_filter", false},
{"node_params.z_min", z_min},
{"node_params.z_max", z_max},
{"node_params.max_queue_size", max_queue_size},
});

RadarThresholdFilterNode node(node_options);
Expand Down Expand Up @@ -78,6 +80,7 @@ TEST(RadarThresholdFilter, isWithinThreshold)
{"node_params.is_z_filter", false},
{"node_params.z_min", z_min},
{"node_params.z_max", z_max},
{"node_params.max_queue_size", max_queue_size},
});

RadarThresholdFilterNode node(node_options);
Expand Down Expand Up @@ -107,6 +110,7 @@ TEST(RadarThresholdFilter, isWithinThreshold)
{"node_params.is_z_filter", false},
{"node_params.z_min", z_min},
{"node_params.z_max", z_max},
{"node_params.max_queue_size", max_queue_size},
});

RadarThresholdFilterNode node(node_options);
Expand Down Expand Up @@ -135,6 +139,7 @@ TEST(RadarThresholdFilter, isWithinThreshold)
{"node_params.is_z_filter", true},
{"node_params.z_min", z_min},
{"node_params.z_max", z_max},
{"node_params.max_queue_size", max_queue_size},
});

RadarThresholdFilterNode node(node_options);
Expand Down

0 comments on commit 78e9c7e

Please sign in to comment.