From 70e445f76b3802d7ec7b235be2fb3f0c1f7821db Mon Sep 17 00:00:00 2001 From: Rodrigo Queiro <rodrigoq@google.com> Date: Wed, 14 Feb 2018 14:21:59 +0100 Subject: [PATCH] Wait for master before getting /use_sim_time This stops RosRun from hanging if started before the rosmaster. The new behaviour is the same as that of rospy: wait for the `rosout` publisher to be registered before continuing to start the node. --- .../org/ros/internal/node/DefaultNode.java | 25 ++++++++++++++----- 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/rosjava/src/main/java/org/ros/internal/node/DefaultNode.java b/rosjava/src/main/java/org/ros/internal/node/DefaultNode.java index e5a4b7c0..9f1a1bdc 100644 --- a/rosjava/src/main/java/org/ros/internal/node/DefaultNode.java +++ b/rosjava/src/main/java/org/ros/internal/node/DefaultNode.java @@ -180,17 +180,26 @@ public class DefaultNode implements ConnectedNode { // possible during startup. registrar.start(slaveServer.toNodeIdentifier()); - // During startup, we wait for 1) the RosoutLogger and 2) the TimeProvider. - final CountDownLatch latch = new CountDownLatch(2); + // Wait for the logger to register with the master. This ensures the master is running before + // requesting the use_sim_time parameter. + final CountDownLatch rosoutLatch = new CountDownLatch(1); log = new RosoutLogger(this); log.getPublisher().addListener(new DefaultPublisherListener<rosgraph_msgs.Log>() { @Override public void onMasterRegistrationSuccess(Publisher<rosgraph_msgs.Log> registrant) { - latch.countDown(); + rosoutLatch.countDown(); } }); + try { + rosoutLatch.await(); + } catch (InterruptedException e) { + signalOnError(e); + shutdown(); + return; + } + boolean useSimTime = false; try { useSimTime = @@ -198,24 +207,28 @@ public class DefaultNode implements ConnectedNode { && parameterTree.getBoolean(Parameters.USE_SIM_TIME); } catch (Exception e) { signalOnError(e); + shutdown(); + return; } + + final CountDownLatch timeLatch = new CountDownLatch(1); if (useSimTime) { ClockTopicTimeProvider clockTopicTimeProvider = new ClockTopicTimeProvider(this); clockTopicTimeProvider.getSubscriber().addSubscriberListener( new DefaultSubscriberListener<rosgraph_msgs.Clock>() { @Override public void onMasterRegistrationSuccess(Subscriber<rosgraph_msgs.Clock> subscriber) { - latch.countDown(); + timeLatch.countDown(); } }); timeProvider = clockTopicTimeProvider; } else { timeProvider = nodeConfiguration.getTimeProvider(); - latch.countDown(); + timeLatch.countDown(); } try { - latch.await(); + timeLatch.await(); } catch (InterruptedException e) { signalOnError(e); shutdown(); -- GitLab