Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
60 changes: 0 additions & 60 deletions realtime_tools/include/realtime_tools/realtime_box.hpp

This file was deleted.

81 changes: 0 additions & 81 deletions realtime_tools/include/realtime_tools/realtime_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,22 +119,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
Expand Down Expand Up @@ -170,71 +154,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_; }
Expand Down
80 changes: 0 additions & 80 deletions realtime_tools/test/realtime_publisher_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Node>("construct_move_destruct");
rclcpp::QoS qos(10);
qos.reliable().transient_local();
auto pub = node->create_publisher<StringMsg>("~/rt_publish", qos);
RealtimePublisher<StringMsg> 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<StringMsg>(
"~/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<rclcpp::Node>("construct_move_destruct");
rclcpp::QoS qos(10);
qos.reliable().transient_local();
auto pub = node->create_publisher<StringMsg>("~/rt_publish", qos);
RealtimePublisher<StringMsg> 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<StringMsg>(
"~/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);
Expand Down