@@ -60,13 +60,15 @@ ScanToScanFilterChain::ScanToScanFilterChain(
6060 #endif
6161 this ->declare_parameter (" tf_message_filter_target_frame" , " " , read_only_desc);
6262 this ->declare_parameter (" tf_message_filter_tolerance" , 0.03 , read_only_desc);
63+ this ->declare_parameter (" scan_filtered_history_depth" , 1000 );
6364
6465 // Get parameters
6566 #ifdef RCLCPP_SUPPORTS_MATCHED_CALLBACKS
6667 this ->get_parameter (" lazy_subscription" , lazy_subscription_);
6768 #endif
6869 this ->get_parameter (" tf_message_filter_target_frame" , tf_message_filter_target_frame_);
6970 this ->get_parameter (" tf_message_filter_tolerance" , tf_filter_tolerance_);
71+ this ->get_parameter (" scan_filtered_history_depth" , scan_filtered_history_depth_);
7072
7173 if (!tf_message_filter_target_frame_.empty ()) {
7274 tf_.reset (new tf2_ros::TransformListener (buffer_));
@@ -103,13 +105,15 @@ ScanToScanFilterChain::ScanToScanFilterChain(
103105 }
104106 };
105107 output_pub_ = this ->create_publisher <sensor_msgs::msg::LaserScan>(
106- " scan_filtered" , 1000 , pub_options);
108+ " scan_filtered" , scan_filtered_history_depth_ , pub_options);
107109 } else {
108- output_pub_ = this ->create_publisher <sensor_msgs::msg::LaserScan>(" scan_filtered" , 1000 );
110+ output_pub_ = this ->create_publisher <sensor_msgs::msg::LaserScan>(
111+ " scan_filtered" , scan_filtered_history_depth_);
109112 scan_sub_.subscribe (this , " scan" , rclcpp::SensorDataQoS ());
110113 }
111114 #else
112- output_pub_ = this ->create_publisher <sensor_msgs::msg::LaserScan>(" scan_filtered" , 1000 );
115+ output_pub_ = this ->create_publisher <sensor_msgs::msg::LaserScan>(
116+ " scan_filtered" , scan_filtered_history_depth_);
113117 scan_sub_.subscribe (this , " scan" , rclcpp::SensorDataQoS ());
114118 #endif
115119}
0 commit comments