Skip to content

Commit 2a36625

Browse files
author
Mauro Passerino
committed
Fix feedback data race
// See ros2#2451 (comment)
1 parent 3c41227 commit 2a36625

File tree

1 file changed

+10
-10
lines changed

1 file changed

+10
-10
lines changed

rclcpp_action/src/client.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -355,16 +355,6 @@ ClientBase::is_ready(rcl_wait_set_t * wait_set)
355355

356356
pimpl_->next_ready_event = ClientBaseImpl::NO_EVENT_READY;
357357

358-
if (is_feedback_ready) {
359-
pimpl_->next_ready_event = static_cast<size_t>(EntityType::FeedbackSubscription);
360-
return true;
361-
}
362-
363-
if (is_status_ready) {
364-
pimpl_->next_ready_event = static_cast<size_t>(EntityType::StatusSubscription);
365-
return true;
366-
}
367-
368358
if (is_goal_response_ready) {
369359
pimpl_->next_ready_event = static_cast<size_t>(EntityType::GoalClient);
370360
return true;
@@ -380,6 +370,16 @@ ClientBase::is_ready(rcl_wait_set_t * wait_set)
380370
return true;
381371
}
382372

373+
if (is_feedback_ready) {
374+
pimpl_->next_ready_event = static_cast<size_t>(EntityType::FeedbackSubscription);
375+
return true;
376+
}
377+
378+
if (is_status_ready) {
379+
pimpl_->next_ready_event = static_cast<size_t>(EntityType::StatusSubscription);
380+
return true;
381+
}
382+
383383
return false;
384384
}
385385

0 commit comments

Comments
 (0)