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.rosjava_tutorial_services;
00018
00019 import org.ros.exception.RemoteException;
00020 import org.ros.exception.RosRuntimeException;
00021 import org.ros.exception.ServiceNotFoundException;
00022 import org.ros.namespace.GraphName;
00023 import org.ros.node.AbstractNodeMain;
00024 import org.ros.node.ConnectedNode;
00025 import org.ros.node.NodeMain;
00026 import org.ros.node.service.ServiceClient;
00027 import org.ros.node.service.ServiceResponseListener;
00028
00034 public class Client extends AbstractNodeMain {
00035
00036 @Override
00037 public GraphName getDefaultNodeName() {
00038 return GraphName.of("rosjava_tutorial_services/client");
00039 }
00040
00041 @Override
00042 public void onStart(final ConnectedNode connectedNode) {
00043 ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
00044 try {
00045 serviceClient = connectedNode.newServiceClient("add_two_ints", rosjava_test_msgs.AddTwoInts._TYPE);
00046 } catch (ServiceNotFoundException e) {
00047 throw new RosRuntimeException(e);
00048 }
00049 final rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
00050 request.setA(2);
00051 request.setB(2);
00052 serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
00053 @Override
00054 public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
00055 connectedNode.getLog().info(
00056 String.format("%d + %d = %d", request.getA(), request.getB(), response.getSum()));
00057 }
00058
00059 @Override
00060 public void onFailure(RemoteException e) {
00061 throw new RosRuntimeException(e);
00062 }
00063 });
00064 }
00065 }