Skip to content

Commit 4192372

Browse files
authored
Fix rviz crash if launch later (#4882)
* Fix rviz crash if start later Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> * Bring back default rviz launch file Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> * New line Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> * Whitespace Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> * Add log when failed Signed-off-by: mini-1235 <mauricepurnawan@gmail.com> --------- Signed-off-by: mini-1235 <mauricepurnawan@gmail.com>
1 parent 1ed7046 commit 4192372

File tree

3 files changed

+37
-41
lines changed

3 files changed

+37
-41
lines changed

nav2_rviz_plugins/include/nav2_rviz_plugins/selector.hpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@
1616
#define NAV2_RVIZ_PLUGINS__SELECTOR_HPP_
1717

1818
#include <QtWidgets>
19-
#include <QBasicTimer>
2019
#include <QFrame>
2120
#include <QGridLayout>
2221
#include <QScrollArea>
@@ -43,22 +42,20 @@ class Selector : public rviz_common::Panel
4342
~Selector();
4443

4544
private:
46-
// The (non-spinning) client node used to invoke the action client
47-
void timerEvent(QTimerEvent * event) override;
45+
void loadPlugins();
4846

4947
rclcpp::Node::SharedPtr client_node_;
5048
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_controller_;
5149
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_planner_;
5250
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_goal_checker_;
5351
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_smoother_;
5452
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_progress_checker_;
55-
rclcpp::TimerBase::SharedPtr rclcpp_timer_;
5653

5754
bool plugins_loaded_ = false;
5855
bool server_failed_ = false;
59-
bool tried_once_ = false;
6056

61-
QBasicTimer timer_;
57+
std::thread load_plugins_thread_;
58+
6259
QVBoxLayout * main_layout_;
6360
QHBoxLayout * row_1_layout_;
6461
QHBoxLayout * row_2_layout_;

nav2_rviz_plugins/src/selector.cpp

Lines changed: 31 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ Selector::Selector(QWidget * parent)
7070
main_layout_->addLayout(row_3_layout_);
7171

7272
setLayout(main_layout_);
73-
timer_.start(200, this);
73+
loadPlugins();
7474

7575
connect(
7676
controller_, QOverload<int>::of(&QComboBox::activated), this,
@@ -115,7 +115,6 @@ void Selector::setSelection(
115115
msg.data = combo_box->currentText().toStdString();
116116

117117
publisher->publish(msg);
118-
timer_.start(200, this);
119118
}
120119

121120
// Call setSelection() for controller
@@ -148,37 +147,37 @@ void Selector::setProgressChecker()
148147
}
149148

150149
void
151-
Selector::timerEvent(QTimerEvent * event)
150+
Selector::loadPlugins()
152151
{
153-
if (event->timerId() == timer_.timerId()) {
154-
if (!plugins_loaded_) {
155-
nav2_rviz_plugins::pluginLoader(
156-
client_node_, server_failed_, "controller_server", "controller_plugins", controller_);
157-
nav2_rviz_plugins::pluginLoader(
158-
client_node_, server_failed_, "planner_server", "planner_plugins", planner_);
159-
nav2_rviz_plugins::pluginLoader(
160-
client_node_, server_failed_, "controller_server", "goal_checker_plugins", goal_checker_);
161-
nav2_rviz_plugins::pluginLoader(
162-
client_node_, server_failed_, "smoother_server", "smoother_plugins", smoother_);
163-
nav2_rviz_plugins::pluginLoader(
164-
client_node_, server_failed_, "controller_server", "progress_checker_plugins",
165-
progress_checker_);
166-
167-
plugins_loaded_ = true;
168-
}
169-
170-
// Restart the timer if the one of the server fails
171-
if (server_failed_ && !tried_once_) {
172-
RCLCPP_INFO(client_node_->get_logger(), "Retrying to connect to the failed server.");
173-
server_failed_ = false;
174-
plugins_loaded_ = false;
175-
tried_once_ = true;
176-
timer_.start(200, this);
177-
return;
178-
}
179-
180-
timer_.stop();
181-
}
152+
load_plugins_thread_ = std::thread([this]() {
153+
rclcpp::Rate rate(0.2);
154+
while (rclcpp::ok() && !plugins_loaded_) {
155+
RCLCPP_INFO(client_node_->get_logger(), "Trying to load plugins...");
156+
nav2_rviz_plugins::pluginLoader(
157+
client_node_, server_failed_, "controller_server", "controller_plugins", controller_);
158+
nav2_rviz_plugins::pluginLoader(
159+
client_node_, server_failed_, "planner_server", "planner_plugins", planner_);
160+
nav2_rviz_plugins::pluginLoader(
161+
client_node_, server_failed_, "controller_server", "goal_checker_plugins",
162+
goal_checker_);
163+
nav2_rviz_plugins::pluginLoader(
164+
client_node_, server_failed_, "smoother_server", "smoother_plugins", smoother_);
165+
nav2_rviz_plugins::pluginLoader(
166+
client_node_, server_failed_, "controller_server", "progress_checker_plugins",
167+
progress_checker_);
168+
if (controller_->count() > 0 &&
169+
planner_->count() > 0 &&
170+
goal_checker_->count() > 0 &&
171+
smoother_->count() > 0 &&
172+
progress_checker_->count() > 0)
173+
{
174+
plugins_loaded_ = true;
175+
} else {
176+
RCLCPP_INFO(client_node_->get_logger(), "Failed to load plugins. Retrying...");
177+
}
178+
rate.sleep();
179+
}
180+
});
182181
}
183182

184183
} // namespace nav2_rviz_plugins

nav2_rviz_plugins/src/utils.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -24,13 +24,13 @@ void pluginLoader(
2424
rclcpp::Node::SharedPtr node, bool & server_failed, const std::string & server_name,
2525
const std::string & plugin_type, QComboBox * combo_box)
2626
{
27-
auto parameter_client = std::make_shared<rclcpp::SyncParametersClient>(node, server_name);
28-
2927
// Do not load the plugins if the combo box is already populated
3028
if (combo_box->count() > 0) {
3129
return;
3230
}
3331

32+
auto parameter_client = std::make_shared<rclcpp::SyncParametersClient>(node, server_name);
33+
3434
// Wait for the service to be available before calling it
3535
bool server_unavailable = false;
3636
while (!parameter_client->wait_for_service(std::chrono::seconds(1))) {
@@ -49,9 +49,9 @@ void pluginLoader(
4949
if (server_unavailable) {
5050
return;
5151
}
52-
combo_box->addItem("Default");
5352
auto parameters = parameter_client->get_parameters({plugin_type});
5453
auto str_arr = parameters[0].as_string_array();
54+
combo_box->addItem("Default");
5555
for (auto str : str_arr) {
5656
combo_box->addItem(QString::fromStdString(str));
5757
}

0 commit comments

Comments
 (0)