Skip to content

Commit e9a8d94

Browse files
Cleanup deprecations
1 parent 02bd7e4 commit e9a8d94

File tree

3 files changed

+0
-221
lines changed

3 files changed

+0
-221
lines changed

realtime_tools/include/realtime_tools/realtime_box.hpp

Lines changed: 0 additions & 60 deletions
This file was deleted.

realtime_tools/include/realtime_tools/realtime_publisher.hpp

Lines changed: 0 additions & 81 deletions
Original file line numberDiff line numberDiff line change
@@ -133,22 +133,6 @@ class RealtimePublisher
133133
updated_cond_.notify_one(); // So the publishing loop can exit
134134
}
135135

136-
/**
137-
* \brief Try to acquire the data lock for non-realtime message publishing
138-
*
139-
* It first checks if the current state allows non-realtime message publishing (turn_ == REALTIME)
140-
* and then attempts to lock
141-
*
142-
* \return true if the lock was successfully acquired, false otherwise
143-
*/
144-
[[deprecated(
145-
"Use try_publish() method instead of this method. This method may be removed in future "
146-
"versions.")]]
147-
bool trylock()
148-
{
149-
return turn_.load(std::memory_order_acquire) == State::REALTIME && msg_mutex_.try_lock();
150-
}
151-
152136
/**
153137
* \brief Check if the realtime publisher is in a state to publish messages
154138
* \return true if the publisher is in a state to publish messages
@@ -196,71 +180,6 @@ class RealtimePublisher
196180
return false;
197181
}
198182

199-
/**
200-
* \brief Try to publish the given message (deprecated)
201-
* \deprecated This method is deprecated and should be replaced with try_publish()
202-
*
203-
* This method is deprecated and should be replaced with try_publish().
204-
* It attempts to publish the given message if the publisher is in a state to do so.
205-
* It uses a try_lock to avoid blocking if the mutex is already held by another thread.
206-
*
207-
* \param [in] msg The message to publish
208-
* \return true if the message was successfully published, false otherwise
209-
*/
210-
[[deprecated(
211-
"Use try_publish() method instead of this method. This method may be removed in future "
212-
"versions.")]]
213-
bool tryPublish(const MessageT & msg)
214-
{
215-
return try_publish(msg);
216-
}
217-
218-
/**
219-
* \brief Unlock the msg_ variable for the non-realtime thread to start publishing
220-
*
221-
* After a successful trylock and after the data is written to the mgs_
222-
* variable, the lock has to be released for the message to get
223-
* published on the specified topic.
224-
*/
225-
[[deprecated(
226-
"Use the try_publish() method to publish the message instead of using this method. This method "
227-
"may be removed in future versions.")]]
228-
void unlockAndPublish()
229-
{
230-
turn_.store(State::NON_REALTIME, std::memory_order_release);
231-
#pragma GCC diagnostic push
232-
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
233-
unlock();
234-
#pragma GCC diagnostic pop
235-
}
236-
237-
/**
238-
* \brief Acquire the data lock
239-
*
240-
* This blocking call acquires exclusive access to the msg_ variable.
241-
* Use trylock() for non-blocking attempts to acquire the lock.
242-
*/
243-
[[deprecated(
244-
"Use the try_publish() method to publish the message instead of using this method. This method "
245-
"may be removed in future versions.")]]
246-
void lock()
247-
{
248-
msg_mutex_.lock();
249-
}
250-
251-
/**
252-
* \brief Unlocks the data without publishing anything
253-
*
254-
*/
255-
[[deprecated(
256-
"Use the try_publish() method to publish the message instead of using this method. This method "
257-
"may be removed in future versions.")]]
258-
void unlock()
259-
{
260-
msg_mutex_.unlock();
261-
updated_cond_.notify_one();
262-
}
263-
264183
std::thread & get_thread() { return thread_; }
265184

266185
const std::thread & get_thread() const { return thread_; }

realtime_tools/test/realtime_publisher_tests.cpp

Lines changed: 0 additions & 80 deletions
Original file line numberDiff line numberDiff line change
@@ -54,86 +54,6 @@ struct StringCallback
5454
}
5555
};
5656

57-
#pragma GCC diagnostic push
58-
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
59-
TEST(RealtimePublisher, rt_publish_legacy)
60-
{
61-
rclcpp::init(0, nullptr);
62-
const size_t ATTEMPTS = 10;
63-
const std::chrono::milliseconds DELAY(250);
64-
65-
const char * expected_msg = "Hello World";
66-
auto node = std::make_shared<rclcpp::Node>("construct_move_destruct");
67-
rclcpp::QoS qos(10);
68-
qos.reliable().transient_local();
69-
auto pub = node->create_publisher<StringMsg>("~/rt_publish", qos);
70-
RealtimePublisher<StringMsg> rt_pub(pub);
71-
// publish a latched message
72-
bool lock_is_held = rt_pub.trylock();
73-
for (size_t i = 0; i < ATTEMPTS && !lock_is_held; ++i) {
74-
lock_is_held = rt_pub.trylock();
75-
std::this_thread::sleep_for(DELAY);
76-
}
77-
ASSERT_TRUE(lock_is_held);
78-
rt_pub.msg_.string_value = expected_msg;
79-
rt_pub.unlockAndPublish();
80-
81-
// make sure subscriber gets it
82-
StringCallback str_callback;
83-
84-
auto sub = node->create_subscription<StringMsg>(
85-
"~/rt_publish", qos,
86-
std::bind(&StringCallback::callback, &str_callback, std::placeholders::_1));
87-
for (size_t i = 0; i < ATTEMPTS && str_callback.msg_.string_value.empty(); ++i) {
88-
rclcpp::spin_some(node);
89-
std::this_thread::sleep_for(DELAY);
90-
}
91-
EXPECT_STREQ(expected_msg, str_callback.msg_.string_value.c_str());
92-
rclcpp::shutdown();
93-
}
94-
95-
TEST(RealtimePublisher, rt_try_publish_legacy)
96-
{
97-
rclcpp::init(0, nullptr);
98-
const size_t ATTEMPTS = 10;
99-
const std::chrono::milliseconds DELAY(250);
100-
101-
const char * expected_msg = "Hello World";
102-
auto node = std::make_shared<rclcpp::Node>("construct_move_destruct");
103-
rclcpp::QoS qos(10);
104-
qos.reliable().transient_local();
105-
auto pub = node->create_publisher<StringMsg>("~/rt_publish", qos);
106-
RealtimePublisher<StringMsg> rt_pub(pub);
107-
108-
// try publish a latched message
109-
bool publish_success = false;
110-
for (std::size_t i = 0; i < ATTEMPTS; ++i) {
111-
StringMsg msg;
112-
msg.string_value = expected_msg;
113-
114-
if (rt_pub.tryPublish(msg)) {
115-
publish_success = true;
116-
break;
117-
}
118-
std::this_thread::sleep_for(DELAY);
119-
}
120-
ASSERT_TRUE(publish_success);
121-
122-
// make sure subscriber gets it
123-
StringCallback str_callback;
124-
125-
auto sub = node->create_subscription<StringMsg>(
126-
"~/rt_publish", qos,
127-
std::bind(&StringCallback::callback, &str_callback, std::placeholders::_1));
128-
for (size_t i = 0; i < ATTEMPTS && str_callback.msg_.string_value.empty(); ++i) {
129-
rclcpp::spin_some(node);
130-
std::this_thread::sleep_for(DELAY);
131-
}
132-
EXPECT_STREQ(expected_msg, str_callback.msg_.string_value.c_str());
133-
rclcpp::shutdown();
134-
}
135-
#pragma GCC diagnostic pop
136-
13757
TEST(RealtimePublisher, rt_can_try_publish)
13858
{
13959
rclcpp::init(0, nullptr);

0 commit comments

Comments
 (0)