MasterRegistrationTest.java
Go to the documentation of this file.
00001 // Copyright 2011 Google Inc. All Rights Reserved.
00002 
00003 package org.ros.internal.node;
00004 
00005 import static org.junit.Assert.assertTrue;
00006 
00007 import org.junit.Test;
00008 import org.ros.RosCore;
00009 import org.ros.RosTest;
00010 import org.ros.namespace.GraphName;
00011 import org.ros.node.AbstractNodeMain;
00012 import org.ros.node.ConnectedNode;
00013 import org.ros.node.topic.CountDownPublisherListener;
00014 import org.ros.node.topic.Publisher;
00015 
00016 import java.io.IOException;
00017 import java.net.URISyntaxException;
00018 import java.util.concurrent.TimeUnit;
00019 
00023 public class MasterRegistrationTest extends RosTest {
00024 
00025   private CountDownPublisherListener<std_msgs.String> publisherListener;
00026   private Publisher<std_msgs.String> publisher;
00027 
00028   @Test
00029   public void testRegisterPublisher() throws InterruptedException {
00030     publisherListener = CountDownPublisherListener.newDefault();
00031     nodeMainExecutor.execute(new AbstractNodeMain() {
00032       @Override
00033       public GraphName getDefaultNodeName() {
00034         return GraphName.of("node");
00035       }
00036 
00037       @Override
00038       public void onStart(ConnectedNode connectedNode) {
00039         publisher = connectedNode.newPublisher("topic", std_msgs.String._TYPE);
00040         publisher.addListener(publisherListener);
00041       }
00042     }, nodeConfiguration);
00043     assertTrue(publisherListener.awaitMasterRegistrationSuccess(1, TimeUnit.SECONDS));
00044     publisher.shutdown();
00045     assertTrue(publisherListener.awaitMasterUnregistrationSuccess(1, TimeUnit.SECONDS));
00046   }
00047 
00048   @Test
00049   public void testRegisterPublisherRetries() throws InterruptedException, IOException,
00050       URISyntaxException {
00051     int port = rosCore.getUri().getPort();
00052     publisherListener = CountDownPublisherListener.newDefault();
00053     nodeMainExecutor.execute(new AbstractNodeMain() {
00054       @Override
00055       public GraphName getDefaultNodeName() {
00056         return GraphName.of("node");
00057       }
00058 
00059       @Override
00060       public void onStart(ConnectedNode connectedNode) {
00061         rosCore.shutdown();
00062         ((DefaultNode) connectedNode).getRegistrar().setRetryDelay(1, TimeUnit.MILLISECONDS);
00063         publisher = connectedNode.newPublisher("topic", std_msgs.String._TYPE);
00064         publisher.addListener(publisherListener);
00065       }
00066     }, nodeConfiguration);
00067 
00068     assertTrue(publisherListener.awaitMasterRegistrationFailure(1, TimeUnit.SECONDS));
00069     rosCore = RosCore.newPrivate(port);
00070     rosCore.start();
00071     assertTrue(rosCore.awaitStart(1, TimeUnit.SECONDS));
00072     assertTrue(publisherListener.awaitMasterRegistrationSuccess(1, TimeUnit.SECONDS));
00073     publisher.shutdown();
00074     assertTrue(publisherListener.awaitMasterUnregistrationSuccess(1, TimeUnit.SECONDS));
00075   }
00076 }


rosjava_core
Author(s):
autogenerated on Wed Aug 26 2015 16:06:49