Skip to content
This repository was archived by the owner on May 31, 2025. It is now read-only.

Commit 3eabcdc

Browse files
knorth55gbiggs
andauthored
show warning in every 10 seconds when manager is not found (#115)
* show warning in 10 seconds when nodelet is not loaded * Update nodelet/src/nodelet.cpp Co-authored-by: Geoffrey Biggs <[email protected]> Co-authored-by: Geoffrey Biggs <[email protected]>
1 parent 8bfcb56 commit 3eabcdc

File tree

1 file changed

+12
-1
lines changed

1 file changed

+12
-1
lines changed

nodelet/src/nodelet.cpp

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -226,9 +226,20 @@ class NodeletInterface
226226
std::string service_name = std::string (manager) + "/load_nodelet";
227227

228228
// Wait until the service is advertised
229+
bool srv_exists = false;
230+
int timeout_sec = 10;
231+
int timeout_count = 0;
229232
ROS_DEBUG ("Waiting for service %s to be available...", service_name.c_str ());
230233
ros::ServiceClient client = n_.serviceClient<nodelet::NodeletLoad> (service_name);
231-
client.waitForExistence ();
234+
while (!srv_exists) {
235+
if (timeout_count > 0) {
236+
ROS_WARN ("Waiting for service %s to be available for %d seconds...", service_name.c_str (), timeout_count * timeout_sec);
237+
}
238+
srv_exists = client.waitForExistence (ros::Duration (timeout_sec));
239+
if (!srv_exists) {
240+
timeout_count += 1;
241+
}
242+
}
232243

233244
// Call the service
234245
nodelet::NodeletLoad srv;

0 commit comments

Comments
 (0)