From eedab07c353e78690c2fe3b64c1acd17dfd2ba2f Mon Sep 17 00:00:00 2001 From: Samuel Lindgren Date: Tue, 23 Aug 2022 14:56:01 +0000 Subject: [PATCH] Increase scan filter queue_size --- src/slam_toolbox_common.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/slam_toolbox_common.cpp b/src/slam_toolbox_common.cpp index 989c9114..9b9405c6 100644 --- a/src/slam_toolbox_common.cpp +++ b/src/slam_toolbox_common.cpp @@ -217,7 +217,7 @@ void SlamToolbox::setROSInterfaces() shared_from_this().get(), scan_topic_, rmw_qos_profile_sensor_data); scan_filter_ = std::make_unique>( - *scan_filter_sub_, *tf_, odom_frame_, 1, shared_from_this(), + *scan_filter_sub_, *tf_, odom_frame_, 5, shared_from_this(), tf2::durationFromSec(transform_timeout_.seconds())); scan_filter_->registerCallback( std::bind(&SlamToolbox::laserCallback, this, std::placeholders::_1));