@@ -70,7 +70,7 @@ Selector::Selector(QWidget * parent)
70
70
main_layout_->addLayout (row_3_layout_);
71
71
72
72
setLayout (main_layout_);
73
- timer_. start ( 200 , this );
73
+ loadPlugins ( );
74
74
75
75
connect (
76
76
controller_, QOverload<int >::of (&QComboBox::activated), this ,
@@ -115,7 +115,6 @@ void Selector::setSelection(
115
115
msg.data = combo_box->currentText ().toStdString ();
116
116
117
117
publisher->publish (msg);
118
- timer_.start (200 , this );
119
118
}
120
119
121
120
// Call setSelection() for controller
@@ -148,37 +147,37 @@ void Selector::setProgressChecker()
148
147
}
149
148
150
149
void
151
- Selector::timerEvent (QTimerEvent * event )
150
+ Selector::loadPlugins ( )
152
151
{
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
+ });
182
181
}
183
182
184
183
} // namespace nav2_rviz_plugins
0 commit comments