From dc964711a0aea2bad65e4b53e151ca6908b0375b Mon Sep 17 00:00:00 2001 From: h-ohta Date: Fri, 5 Jan 2024 11:01:36 +0900 Subject: [PATCH] Revert "feat(imu_corrector): change subscription reliability to best_effort" This reverts commit 8fbe2034b09536277e75c468f18a081ec448193c. --- sensing/imu_corrector/src/imu_corrector_core.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sensing/imu_corrector/src/imu_corrector_core.cpp b/sensing/imu_corrector/src/imu_corrector_core.cpp index 8c2cecac89b00..a26c64925729c 100644 --- a/sensing/imu_corrector/src/imu_corrector_core.cpp +++ b/sensing/imu_corrector/src/imu_corrector_core.cpp @@ -72,7 +72,7 @@ ImuCorrector::ImuCorrector() accel_stddev_imu_link_ = declare_parameter("acceleration_stddev", 10000.0); imu_sub_ = create_subscription( - "input", rclcpp::SensorDataQoS().keep_last(1), std::bind(&ImuCorrector::callbackImu, this, std::placeholders::_1)); + "input", rclcpp::QoS{1}, std::bind(&ImuCorrector::callbackImu, this, std::placeholders::_1)); imu_pub_ = create_publisher("output", rclcpp::QoS{10}); }