@@ -95,19 +95,26 @@ RadarStaticPointcloudFilterNode::RadarStaticPointcloudFilterNode(
95
95
96
96
// Node Parameter
97
97
node_param_.doppler_velocity_sd = declare_parameter<double >(" doppler_velocity_sd" );
98
+ node_param_.max_queue_size = declare_parameter<int64_t >(" max_queue_size" );
98
99
99
100
// Subscriber
100
101
transform_listener_ = std::make_shared<autoware_utils::TransformListener>(this );
101
102
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 ());
104
109
105
110
sync_ptr_ = std::make_shared<Sync>(SyncPolicy (10 ), sub_radar_, sub_odometry_);
106
111
sync_ptr_->registerCallback (std::bind (&RadarStaticPointcloudFilterNode::onData, this , _1, _2));
107
112
108
113
// 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 ));
111
118
}
112
119
113
120
rcl_interfaces::msg::SetParametersResult RadarStaticPointcloudFilterNode::onSetParam (
@@ -117,6 +124,7 @@ rcl_interfaces::msg::SetParametersResult RadarStaticPointcloudFilterNode::onSetP
117
124
try {
118
125
auto & p = node_param_;
119
126
update_param (params, " doppler_velocity_sd" , p.doppler_velocity_sd );
127
+ update_param (params, " max_queue_size" , p.max_queue_size );
120
128
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
121
129
result.successful = false ;
122
130
result.reason = e.what ();
0 commit comments