From 796415e1607840e9c0928feece8c87fb1be8baf3 Mon Sep 17 00:00:00 2001 From: Michael Ferguson Date: Sun, 11 Aug 2024 11:00:29 -0400 Subject: [PATCH] remove redundant keep_last() (#166) --- robot_calibration/src/finders/led_finder.cpp | 2 +- robot_calibration/src/finders/plane_finder.cpp | 2 +- robot_calibration/src/finders/scan_finder.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/robot_calibration/src/finders/led_finder.cpp b/robot_calibration/src/finders/led_finder.cpp index 4b72e1f6..64f1bfb3 100644 --- a/robot_calibration/src/finders/led_finder.cpp +++ b/robot_calibration/src/finders/led_finder.cpp @@ -71,7 +71,7 @@ bool LedFinder::init(const std::string& name, topic_name = node->declare_parameter(name + ".topic", name + "/points"); subscriber_ = node->create_subscription( topic_name, - rclcpp::QoS(1).best_effort().keep_last(1), + rclcpp::QoS(1).best_effort(), std::bind(&LedFinder::cameraCallback, this, std::placeholders::_1)); // Publish where LEDs were seen diff --git a/robot_calibration/src/finders/plane_finder.cpp b/robot_calibration/src/finders/plane_finder.cpp index cee30391..7c32d330 100644 --- a/robot_calibration/src/finders/plane_finder.cpp +++ b/robot_calibration/src/finders/plane_finder.cpp @@ -108,7 +108,7 @@ bool PlaneFinder::init(const std::string& name, node->declare_parameter(name + ".topic", name + "/points"); subscriber_ = node->create_subscription( topic_name, - rclcpp::QoS(1).best_effort().keep_last(1), + rclcpp::QoS(1).best_effort(), std::bind(&PlaneFinder::cameraCallback, this, std::placeholders::_1)); // Name of the sensor model that will be used during optimization diff --git a/robot_calibration/src/finders/scan_finder.cpp b/robot_calibration/src/finders/scan_finder.cpp index 1e960b9d..bc7ab3b1 100644 --- a/robot_calibration/src/finders/scan_finder.cpp +++ b/robot_calibration/src/finders/scan_finder.cpp @@ -53,7 +53,7 @@ bool ScanFinder::init(const std::string& name, topic_name = node->declare_parameter(name + ".topic", name + "/scan"); subscriber_ = node->create_subscription( topic_name, - rclcpp::QoS(1).best_effort().keep_last(1), + rclcpp::QoS(1).best_effort(), std::bind(&ScanFinder::scanCallback, this, std::placeholders::_1)); // Name of the sensor model that will be used during optimization