Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 package org.ros.node.service;
00018
00019 import static org.junit.Assert.assertEquals;
00020 import static org.junit.Assert.assertTrue;
00021 import static org.junit.Assert.fail;
00022
00023 import org.junit.Test;
00024 import org.ros.RosTest;
00025 import org.ros.exception.DuplicateServiceException;
00026 import org.ros.exception.RemoteException;
00027 import org.ros.exception.RosRuntimeException;
00028 import org.ros.exception.ServiceException;
00029 import org.ros.exception.ServiceNotFoundException;
00030 import org.ros.namespace.GraphName;
00031 import org.ros.node.AbstractNodeMain;
00032 import org.ros.node.ConnectedNode;
00033
00034 import java.util.concurrent.CountDownLatch;
00035 import java.util.concurrent.TimeUnit;
00036
00040 public class ServiceIntegrationTest extends RosTest {
00041
00042 private static final String SERVICE_NAME = "/add_two_ints";
00043
00044 @Test
00045 public void testPesistentServiceConnection() throws Exception {
00046 final CountDownServiceServerListener<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> countDownServiceServerListener =
00047 CountDownServiceServerListener.newDefault();
00048 nodeMainExecutor.execute(new AbstractNodeMain() {
00049 @Override
00050 public GraphName getDefaultNodeName() {
00051 return GraphName.of("server");
00052 }
00053
00054 @Override
00055 public void onStart(final ConnectedNode connectedNode) {
00056 ServiceServer<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceServer =
00057 connectedNode
00058 .newServiceServer(
00059 SERVICE_NAME,
00060 rosjava_test_msgs.AddTwoInts._TYPE,
00061 new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
00062 @Override
00063 public void build(rosjava_test_msgs.AddTwoIntsRequest request,
00064 rosjava_test_msgs.AddTwoIntsResponse response) {
00065 response.setSum(request.getA() + request.getB());
00066 }
00067 });
00068 try {
00069 connectedNode.newServiceServer(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE, null);
00070 fail();
00071 } catch (DuplicateServiceException e) {
00072
00073 }
00074 serviceServer.addListener(countDownServiceServerListener);
00075 }
00076 }, nodeConfiguration);
00077
00078 assertTrue(countDownServiceServerListener.awaitMasterRegistrationSuccess(1, TimeUnit.SECONDS));
00079
00080 final CountDownLatch latch = new CountDownLatch(2);
00081 nodeMainExecutor.execute(new AbstractNodeMain() {
00082 @Override
00083 public GraphName getDefaultNodeName() {
00084 return GraphName.of("client");
00085 }
00086
00087 @Override
00088 public void onStart(ConnectedNode connectedNode) {
00089 ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
00090 try {
00091 serviceClient = connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
00092
00093
00094 ServiceClient<?, ?> duplicate =
00095 connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
00096 assertEquals(serviceClient, duplicate);
00097 } catch (ServiceNotFoundException e) {
00098 throw new RosRuntimeException(e);
00099 }
00100 rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
00101 request.setA(2);
00102 request.setB(2);
00103 serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
00104 @Override
00105 public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
00106 assertEquals(response.getSum(), 4);
00107 latch.countDown();
00108 }
00109
00110 @Override
00111 public void onFailure(RemoteException e) {
00112 throw new RuntimeException(e);
00113 }
00114 });
00115
00116
00117 request.setA(3);
00118 request.setB(3);
00119 serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
00120 @Override
00121 public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
00122 assertEquals(response.getSum(), 6);
00123 latch.countDown();
00124 }
00125
00126 @Override
00127 public void onFailure(RemoteException e) {
00128 throw new RuntimeException(e);
00129 }
00130 });
00131 }
00132 }, nodeConfiguration);
00133
00134 assertTrue(latch.await(1, TimeUnit.SECONDS));
00135 }
00136
00137 @Test
00138 public void testRequestFailure() throws Exception {
00139 final String errorMessage = "Error!";
00140 final CountDownServiceServerListener<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> countDownServiceServerListener =
00141 CountDownServiceServerListener.newDefault();
00142 nodeMainExecutor.execute(new AbstractNodeMain() {
00143 @Override
00144 public GraphName getDefaultNodeName() {
00145 return GraphName.of("server");
00146 }
00147
00148 @Override
00149 public void onStart(ConnectedNode connectedNode) {
00150 ServiceServer<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceServer =
00151 connectedNode
00152 .newServiceServer(
00153 SERVICE_NAME,
00154 rosjava_test_msgs.AddTwoInts._TYPE,
00155 new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
00156 @Override
00157 public void build(rosjava_test_msgs.AddTwoIntsRequest request,
00158 rosjava_test_msgs.AddTwoIntsResponse response) throws ServiceException {
00159 throw new ServiceException(errorMessage);
00160 }
00161 });
00162 serviceServer.addListener(countDownServiceServerListener);
00163 }
00164 }, nodeConfiguration);
00165
00166 assertTrue(countDownServiceServerListener.awaitMasterRegistrationSuccess(1, TimeUnit.SECONDS));
00167
00168 final CountDownLatch latch = new CountDownLatch(1);
00169 nodeMainExecutor.execute(new AbstractNodeMain() {
00170 @Override
00171 public GraphName getDefaultNodeName() {
00172 return GraphName.of("client");
00173 }
00174
00175 @Override
00176 public void onStart(ConnectedNode connectedNode) {
00177 ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
00178 try {
00179 serviceClient = connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
00180 } catch (ServiceNotFoundException e) {
00181 throw new RosRuntimeException(e);
00182 }
00183 rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
00184 serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
00185 @Override
00186 public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse message) {
00187 fail();
00188 }
00189
00190 @Override
00191 public void onFailure(RemoteException e) {
00192 assertEquals(e.getMessage(), errorMessage);
00193 latch.countDown();
00194 }
00195 });
00196 }
00197 }, nodeConfiguration);
00198
00199 assertTrue(latch.await(1, TimeUnit.SECONDS));
00200 }
00201 }