From e9a8d948da22513aeaefb9bb42585225ad318e06 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Sat, 26 Jul 2025 10:31:35 +0000 Subject: [PATCH 1/3] Cleanup deprecations --- .../include/realtime_tools/realtime_box.hpp | 60 -------------- .../realtime_tools/realtime_publisher.hpp | 81 ------------------- .../test/realtime_publisher_tests.cpp | 80 ------------------ 3 files changed, 221 deletions(-) delete mode 100644 realtime_tools/include/realtime_tools/realtime_box.hpp diff --git a/realtime_tools/include/realtime_tools/realtime_box.hpp b/realtime_tools/include/realtime_tools/realtime_box.hpp deleted file mode 100644 index 4b5458a4..00000000 --- a/realtime_tools/include/realtime_tools/realtime_box.hpp +++ /dev/null @@ -1,60 +0,0 @@ -// Copyright (c) 2009, Willow Garage, Inc. -// Copyright (c) 2024, Lennart Nachtigall -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the Willow Garage, Inc. nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -// Author: Stuart Glaser -// Author: Lennart Nachtigall - -#ifndef REALTIME_TOOLS__REALTIME_BOX_HPP_ -#define REALTIME_TOOLS__REALTIME_BOX_HPP_ - -#include "realtime_tools/realtime_thread_safe_box.hpp" - -// Deprecation notice -#pragma message( \ - "'RealtimeBox' is deprecated. Please update your code to use 'realtime_thread_safe_box.hpp' header, and class name 'RealtimeThreadSafeBox' instead.") //NOLINT - -namespace realtime_tools -{ - -// Provide backward-compatibility for the old RealtimeBox class -template -using RealtimeBoxBase = RealtimeThreadSafeBox; - -template -using RealtimeBoxStandard = RealtimeBoxBase; - -template -using RealtimeBoxRecursive = RealtimeBoxBase; - -template -using RealtimeBox = RealtimeBoxStandard; - -} // namespace realtime_tools - -#endif // REALTIME_TOOLS__REALTIME_BOX_HPP_ diff --git a/realtime_tools/include/realtime_tools/realtime_publisher.hpp b/realtime_tools/include/realtime_tools/realtime_publisher.hpp index 1d49a771..c6a93763 100644 --- a/realtime_tools/include/realtime_tools/realtime_publisher.hpp +++ b/realtime_tools/include/realtime_tools/realtime_publisher.hpp @@ -133,22 +133,6 @@ class RealtimePublisher updated_cond_.notify_one(); // So the publishing loop can exit } - /** - * \brief Try to acquire the data lock for non-realtime message publishing - * - * It first checks if the current state allows non-realtime message publishing (turn_ == REALTIME) - * and then attempts to lock - * - * \return true if the lock was successfully acquired, false otherwise - */ - [[deprecated( - "Use try_publish() method instead of this method. This method may be removed in future " - "versions.")]] - bool trylock() - { - return turn_.load(std::memory_order_acquire) == State::REALTIME && msg_mutex_.try_lock(); - } - /** * \brief Check if the realtime publisher is in a state to publish messages * \return true if the publisher is in a state to publish messages @@ -196,71 +180,6 @@ class RealtimePublisher return false; } - /** - * \brief Try to publish the given message (deprecated) - * \deprecated This method is deprecated and should be replaced with try_publish() - * - * This method is deprecated and should be replaced with try_publish(). - * It attempts to publish the given message if the publisher is in a state to do so. - * It uses a try_lock to avoid blocking if the mutex is already held by another thread. - * - * \param [in] msg The message to publish - * \return true if the message was successfully published, false otherwise - */ - [[deprecated( - "Use try_publish() method instead of this method. This method may be removed in future " - "versions.")]] - bool tryPublish(const MessageT & msg) - { - return try_publish(msg); - } - - /** - * \brief Unlock the msg_ variable for the non-realtime thread to start publishing - * - * After a successful trylock and after the data is written to the mgs_ - * variable, the lock has to be released for the message to get - * published on the specified topic. - */ - [[deprecated( - "Use the try_publish() method to publish the message instead of using this method. This method " - "may be removed in future versions.")]] - void unlockAndPublish() - { - turn_.store(State::NON_REALTIME, std::memory_order_release); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - unlock(); -#pragma GCC diagnostic pop - } - - /** - * \brief Acquire the data lock - * - * This blocking call acquires exclusive access to the msg_ variable. - * Use trylock() for non-blocking attempts to acquire the lock. - */ - [[deprecated( - "Use the try_publish() method to publish the message instead of using this method. This method " - "may be removed in future versions.")]] - void lock() - { - msg_mutex_.lock(); - } - - /** - * \brief Unlocks the data without publishing anything - * - */ - [[deprecated( - "Use the try_publish() method to publish the message instead of using this method. This method " - "may be removed in future versions.")]] - void unlock() - { - msg_mutex_.unlock(); - updated_cond_.notify_one(); - } - std::thread & get_thread() { return thread_; } const std::thread & get_thread() const { return thread_; } diff --git a/realtime_tools/test/realtime_publisher_tests.cpp b/realtime_tools/test/realtime_publisher_tests.cpp index 38fcca24..2c44ebfc 100644 --- a/realtime_tools/test/realtime_publisher_tests.cpp +++ b/realtime_tools/test/realtime_publisher_tests.cpp @@ -54,86 +54,6 @@ struct StringCallback } }; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST(RealtimePublisher, rt_publish_legacy) -{ - rclcpp::init(0, nullptr); - const size_t ATTEMPTS = 10; - const std::chrono::milliseconds DELAY(250); - - const char * expected_msg = "Hello World"; - auto node = std::make_shared("construct_move_destruct"); - rclcpp::QoS qos(10); - qos.reliable().transient_local(); - auto pub = node->create_publisher("~/rt_publish", qos); - RealtimePublisher rt_pub(pub); - // publish a latched message - bool lock_is_held = rt_pub.trylock(); - for (size_t i = 0; i < ATTEMPTS && !lock_is_held; ++i) { - lock_is_held = rt_pub.trylock(); - std::this_thread::sleep_for(DELAY); - } - ASSERT_TRUE(lock_is_held); - rt_pub.msg_.string_value = expected_msg; - rt_pub.unlockAndPublish(); - - // make sure subscriber gets it - StringCallback str_callback; - - auto sub = node->create_subscription( - "~/rt_publish", qos, - std::bind(&StringCallback::callback, &str_callback, std::placeholders::_1)); - for (size_t i = 0; i < ATTEMPTS && str_callback.msg_.string_value.empty(); ++i) { - rclcpp::spin_some(node); - std::this_thread::sleep_for(DELAY); - } - EXPECT_STREQ(expected_msg, str_callback.msg_.string_value.c_str()); - rclcpp::shutdown(); -} - -TEST(RealtimePublisher, rt_try_publish_legacy) -{ - rclcpp::init(0, nullptr); - const size_t ATTEMPTS = 10; - const std::chrono::milliseconds DELAY(250); - - const char * expected_msg = "Hello World"; - auto node = std::make_shared("construct_move_destruct"); - rclcpp::QoS qos(10); - qos.reliable().transient_local(); - auto pub = node->create_publisher("~/rt_publish", qos); - RealtimePublisher rt_pub(pub); - - // try publish a latched message - bool publish_success = false; - for (std::size_t i = 0; i < ATTEMPTS; ++i) { - StringMsg msg; - msg.string_value = expected_msg; - - if (rt_pub.tryPublish(msg)) { - publish_success = true; - break; - } - std::this_thread::sleep_for(DELAY); - } - ASSERT_TRUE(publish_success); - - // make sure subscriber gets it - StringCallback str_callback; - - auto sub = node->create_subscription( - "~/rt_publish", qos, - std::bind(&StringCallback::callback, &str_callback, std::placeholders::_1)); - for (size_t i = 0; i < ATTEMPTS && str_callback.msg_.string_value.empty(); ++i) { - rclcpp::spin_some(node); - std::this_thread::sleep_for(DELAY); - } - EXPECT_STREQ(expected_msg, str_callback.msg_.string_value.c_str()); - rclcpp::shutdown(); -} -#pragma GCC diagnostic pop - TEST(RealtimePublisher, rt_can_try_publish) { rclcpp::init(0, nullptr); From 9e26e41bc49f9439cc9754bd5941c615a8599098 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 3 Oct 2025 22:03:20 +0000 Subject: [PATCH 2/3] Make msg_ variable private --- .../include/realtime_tools/realtime_publisher.hpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/realtime_tools/include/realtime_tools/realtime_publisher.hpp b/realtime_tools/include/realtime_tools/realtime_publisher.hpp index c6a93763..d774a453 100644 --- a/realtime_tools/include/realtime_tools/realtime_publisher.hpp +++ b/realtime_tools/include/realtime_tools/realtime_publisher.hpp @@ -63,10 +63,6 @@ class RealtimePublisher RCLCPP_SMART_PTR_DEFINITIONS(RealtimePublisher) - [[deprecated( - "This variable is deprecated, it is recommended to use the try_publish() method instead.")]] - MessageT msg_; - /** * \brief Constructor for the realtime publisher * @@ -278,6 +274,8 @@ class RealtimePublisher std::thread thread_; + MessageT msg_; + mutable std::mutex msg_mutex_; // Protects msg_ std::condition_variable updated_cond_; From c039a202fd2791d45b888d8926290b103a555875 Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Sun, 5 Oct 2025 17:54:31 +0000 Subject: [PATCH 3/3] Remove get_msg method --- .../realtime_tools/realtime_publisher.hpp | 56 ------------------- 1 file changed, 56 deletions(-) diff --git a/realtime_tools/include/realtime_tools/realtime_publisher.hpp b/realtime_tools/include/realtime_tools/realtime_publisher.hpp index d774a453..368804c8 100644 --- a/realtime_tools/include/realtime_tools/realtime_publisher.hpp +++ b/realtime_tools/include/realtime_tools/realtime_publisher.hpp @@ -72,13 +72,6 @@ class RealtimePublisher * * \param publisher the ROS publisher to wrap */ -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable : 4996) -#else -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#endif explicit RealtimePublisher(PublisherSharedPtr publisher) : publisher_(publisher), is_running_(false), keep_running_(true), turn_(State::LOOP_NOT_STARTED) { @@ -107,11 +100,6 @@ class RealtimePublisher thread_.join(); } } -#ifdef _MSC_VER -#pragma warning(pop) -#else -#pragma GCC diagnostic pop -#endif /** * \brief Stop the realtime publisher @@ -155,19 +143,7 @@ class RealtimePublisher if (can_publish(lock)) { { std::unique_lock scoped_lock(std::move(lock)); -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable : 4996) -#else -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#endif msg_ = msg; -#ifdef _MSC_VER -#pragma warning(pop) -#else -#pragma GCC diagnostic pop -#endif turn_.store(State::NON_REALTIME, std::memory_order_release); } updated_cond_.notify_one(); // Notify the publishing thread @@ -180,26 +156,6 @@ class RealtimePublisher const std::thread & get_thread() const { return thread_; } - [[deprecated( - "This getter method will be removed. It is recommended to use the try_publish() instead of " - "accessing the msg_ variable.")]] - const MessageT & get_msg() const - { -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable : 4996) -#else -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#endif - return msg_; -#ifdef _MSC_VER -#pragma warning(pop) -#else -#pragma GCC diagnostic pop -#endif - } - std::mutex & get_mutex() { return msg_mutex_; } const std::mutex & get_mutex() const { return msg_mutex_; } @@ -245,19 +201,7 @@ class RealtimePublisher // Locks msg_ and copies it to outgoing std::unique_lock lock_(msg_mutex_); updated_cond_.wait(lock_, [&] { return turn_ == State::NON_REALTIME || !keep_running_; }); -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable : 4996) -#else -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#endif outgoing = msg_; -#ifdef _MSC_VER -#pragma warning(pop) -#else -#pragma GCC diagnostic pop -#endif } // Sends the outgoing message