Skip to content

Commit

Permalink
fixing the race condition
Browse files Browse the repository at this point in the history
Signed-off-by: PRP <[email protected]>
  • Loading branch information
padhupradheep committed Feb 8, 2024
1 parent c2486ff commit 605e465
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 1 deletion.
2 changes: 2 additions & 0 deletions nav2_rviz_plugins/include/nav2_rviz_plugins/selector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ class Selector : public rviz_common::Panel
rclcpp::TimerBase::SharedPtr rclcpp_timer_;

bool plugins_loaded_ = false;
bool server_failed_ = false;
bool tried_once_ = false;

QBasicTimer timer_;
QHBoxLayout * main_layout_;
Expand Down
19 changes: 18 additions & 1 deletion nav2_rviz_plugins/src/selector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,9 +133,14 @@ void Selector::pluginLoader(
{
auto parameter_client = std::make_shared<rclcpp::SyncParametersClient>(node, server_name);

// Do not load the plugins if the combo box is already populated
if (combo_box->count() > 0) {
return;
}

// Wait for the service to be available before calling it
bool server_unavailable = false;
while (!parameter_client->wait_for_service(3s)) {
while (!parameter_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.");
rclcpp::shutdown();
Expand All @@ -144,6 +149,7 @@ void Selector::pluginLoader(
node->get_logger(),
(server_name + " service not available").c_str());
server_unavailable = true;
server_failed_ = true;
break;
}

Expand Down Expand Up @@ -175,6 +181,17 @@ Selector::timerEvent(QTimerEvent * event)

plugins_loaded_ = true;
}

// Restart the timer if the one of the server fails
if (server_failed_ && !tried_once_) {
RCLCPP_INFO(client_node_->get_logger(), "Retrying to connect to the failed server.");
server_failed_ = false;
plugins_loaded_ = false;
tried_once_ = true;
timer_.start(200, this);
return;
}

timer_.stop();
}
}
Expand Down

0 comments on commit 605e465

Please sign in to comment.