Skip to content

Commit 5d6d95e

Browse files
committed
fix(autoware_radar_static_pointcloud_filter): use correct qos
Signed-off-by: Mehmet Emin BAŞOĞLU <mehmeteminbasoglu@hotmail.com>
1 parent 1ed8e32 commit 5d6d95e

4 files changed

+21
-5
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
11
/**:
22
ros__parameters:
33
doppler_velocity_sd: 4.0
4+
max_queue_size: 5

sensing/autoware_radar_static_pointcloud_filter/schema/radar_static_pointcloud_filter.schema.json

+7-1
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,15 @@
1111
"default": "4.0",
1212
"minimum": 0.0,
1313
"description": "Standard deviation for radar doppler velocity. [m/s]"
14+
},
15+
"max_queue_size": {
16+
"type": "integer",
17+
"default": "5",
18+
"minimum": 1,
19+
"description": "Max queue size of input/output topics."
1420
}
1521
},
16-
"required": ["doppler_velocity_sd"]
22+
"required": ["doppler_velocity_sd", "max_queue_size"]
1723
}
1824
},
1925
"properties": {

sensing/autoware_radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node.cpp

+12-4
Original file line numberDiff line numberDiff line change
@@ -95,19 +95,26 @@ RadarStaticPointcloudFilterNode::RadarStaticPointcloudFilterNode(
9595

9696
// Node Parameter
9797
node_param_.doppler_velocity_sd = declare_parameter<double>("doppler_velocity_sd");
98+
node_param_.max_queue_size = declare_parameter<int64_t>("max_queue_size");
9899

99100
// Subscriber
100101
transform_listener_ = std::make_shared<autoware_utils::TransformListener>(this);
101102

102-
sub_radar_.subscribe(this, "~/input/radar", rclcpp::QoS{1}.get_rmw_qos_profile());
103-
sub_odometry_.subscribe(this, "~/input/odometry", rclcpp::QoS{1}.get_rmw_qos_profile());
103+
sub_radar_.subscribe(
104+
this, "~/input/radar",
105+
rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size).get_rmw_qos_profile());
106+
sub_odometry_.subscribe(
107+
this, "~/input/odometry",
108+
rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size).get_rmw_qos_profile());
104109

105110
sync_ptr_ = std::make_shared<Sync>(SyncPolicy(10), sub_radar_, sub_odometry_);
106111
sync_ptr_->registerCallback(std::bind(&RadarStaticPointcloudFilterNode::onData, this, _1, _2));
107112

108113
// Publisher
109-
pub_static_radar_ = create_publisher<RadarScan>("~/output/static_radar_scan", 1);
110-
pub_dynamic_radar_ = create_publisher<RadarScan>("~/output/dynamic_radar_scan", 1);
114+
pub_static_radar_ = create_publisher<RadarScan>(
115+
"~/output/static_radar_scan", rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size));
116+
pub_dynamic_radar_ = create_publisher<RadarScan>(
117+
"~/output/dynamic_radar_scan", rclcpp::SensorDataQoS().keep_last(node_param_.max_queue_size));
111118
}
112119

113120
rcl_interfaces::msg::SetParametersResult RadarStaticPointcloudFilterNode::onSetParam(
@@ -117,6 +124,7 @@ rcl_interfaces::msg::SetParametersResult RadarStaticPointcloudFilterNode::onSetP
117124
try {
118125
auto & p = node_param_;
119126
update_param(params, "doppler_velocity_sd", p.doppler_velocity_sd);
127+
update_param(params, "max_queue_size", p.max_queue_size);
120128
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
121129
result.successful = false;
122130
result.reason = e.what();

sensing/autoware_radar_static_pointcloud_filter/src/radar_static_pointcloud_filter_node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@ class RadarStaticPointcloudFilterNode : public rclcpp::Node
4545
struct NodeParam
4646
{
4747
double doppler_velocity_sd{};
48+
size_t max_queue_size{};
4849
};
4950

5051
private:

0 commit comments

Comments
 (0)