@@ -78,6 +78,14 @@ class RealtimePublisher
78
78
: publisher_(publisher), is_running_(false ), keep_running_(true ), turn_(State::LOOP_NOT_STARTED)
79
79
{
80
80
thread_ = std::thread (&RealtimePublisher::publishingLoop, this );
81
+
82
+ // Wait for the thread to be ready before proceeding
83
+ // This is important to ensure that the thread is properly initialized and ready to handle
84
+ // messages before any other operations are performed on the RealtimePublisher instance.
85
+ while (!thread_.joinable () ||
86
+ turn_.load (std::memory_order_acquire) == State::LOOP_NOT_STARTED) {
87
+ std::this_thread::sleep_for (std::chrono::microseconds (100 ));
88
+ }
81
89
}
82
90
83
91
[[deprecated(
@@ -116,14 +124,14 @@ class RealtimePublisher
116
124
/* *
117
125
* \brief Try to acquire the data lock for non-realtime message publishing
118
126
*
119
- * It first checks if the current state allows non-realtime message publishing (turn_ == NON_REALTIME )
127
+ * It first checks if the current state allows non-realtime message publishing (turn_ == REALTIME )
120
128
* and then attempts to lock
121
129
*
122
130
* \return true if the lock was successfully acquired, false otherwise
123
131
*/
124
132
bool trylock ()
125
133
{
126
- if (turn_.load (std::memory_order_acquire) == State::NON_REALTIME && msg_mutex_.try_lock ()) {
134
+ if (turn_.load (std::memory_order_acquire) == State::REALTIME && msg_mutex_.try_lock ()) {
127
135
return true ;
128
136
} else {
129
137
return false ;
@@ -159,7 +167,7 @@ class RealtimePublisher
159
167
*/
160
168
void unlockAndPublish ()
161
169
{
162
- turn_.store (State::REALTIME , std::memory_order_release);
170
+ turn_.store (State::NON_REALTIME , std::memory_order_release);
163
171
unlock ();
164
172
}
165
173
@@ -196,33 +204,32 @@ class RealtimePublisher
196
204
* \brief Publishing loop (runs in separate thread)
197
205
*
198
206
* This is the main loop for the non-realtime publishing thread. It:
199
- * 1. Waits for new messages (State::REALTIME )
207
+ * 1. Waits for new messages (State::NON_REALTIME )
200
208
* 2. Copies the message data
201
209
* 3. Publishes the message through the ROS publisher
202
- * 4. Returns to State::NON_REALTIME to allow realtime updates
210
+ * 4. Returns to State::REALTIME to allow realtime updates
203
211
*
204
212
* The loop continues until keep_running_ is set to false.
205
213
*/
206
214
void publishingLoop ()
207
215
{
208
216
is_running_ = true ;
209
- turn_.store (State::NON_REALTIME, std::memory_order_release);
210
217
211
218
while (keep_running_) {
212
219
MessageT outgoing;
213
220
214
221
{
222
+ turn_.store (State::REALTIME, std::memory_order_release);
215
223
// Locks msg_ and copies it to outgoing
216
224
std::unique_lock<std::mutex> lock_ (msg_mutex_);
217
- updated_cond_.wait (lock_, [&] { return turn_ == State::REALTIME || !keep_running_; });
225
+ updated_cond_.wait (lock_, [&] { return turn_ == State::NON_REALTIME || !keep_running_; });
218
226
outgoing = msg_;
219
227
}
220
228
221
229
// Sends the outgoing message
222
230
if (keep_running_) {
223
231
publisher_->publish (outgoing);
224
232
}
225
- turn_.store (State::NON_REALTIME, std::memory_order_release);
226
233
}
227
234
is_running_ = false ;
228
235
}
0 commit comments