Skip to content
Snippets Groups Projects
Commit b907b490 authored by Damon Kohler's avatar Damon Kohler
Browse files

Fix build.gradle to include latest Guava.

Change services to create named request and response messages (previously anonymous).
parent 36e49711
Branches
Tags
No related merge requests found
......@@ -43,7 +43,7 @@ public class ServiceIntegrationTest extends RosTest {
@Test
public void testPesistentServiceConnection() throws Exception {
final CountDownServiceServerListener<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response> countDownServiceServerListener =
final CountDownServiceServerListener<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> countDownServiceServerListener =
CountDownServiceServerListener.newDefault();
nodeMainExecutor.execute(new AbstractNodeMain() {
@Override
......@@ -53,15 +53,15 @@ public class ServiceIntegrationTest extends RosTest {
@Override
public void onStart(final ConnectedNode connectedNode) {
ServiceServer<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response> serviceServer =
ServiceServer<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceServer =
connectedNode
.newServiceServer(
SERVICE_NAME,
test_ros.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response>() {
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
@Override
public void build(test_ros.AddTwoInts.Request request,
test_ros.AddTwoInts.Response response) {
public void build(test_ros.AddTwoIntsRequest request,
test_ros.AddTwoIntsResponse response) {
response.setSum(request.getA() + request.getB());
}
});
......@@ -86,7 +86,7 @@ public class ServiceIntegrationTest extends RosTest {
@Override
public void onStart(ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response> serviceClient;
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
try {
serviceClient = connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE);
// Test that requesting another client for the same service returns
......@@ -97,12 +97,12 @@ public class ServiceIntegrationTest extends RosTest {
} catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e);
}
test_ros.AddTwoInts.Request request = serviceClient.newMessage();
test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
request.setA(2);
request.setB(2);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoInts.Response>() {
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
@Override
public void onSuccess(test_ros.AddTwoInts.Response response) {
public void onSuccess(test_ros.AddTwoIntsResponse response) {
assertEquals(response.getSum(), 4);
latch.countDown();
}
......@@ -121,7 +121,7 @@ public class ServiceIntegrationTest extends RosTest {
@Test
public void testRequestFailure() throws Exception {
final String errorMessage = "Error!";
final CountDownServiceServerListener<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response> countDownServiceServerListener =
final CountDownServiceServerListener<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> countDownServiceServerListener =
CountDownServiceServerListener.newDefault();
nodeMainExecutor.execute(new AbstractNodeMain() {
@Override
......@@ -131,15 +131,15 @@ public class ServiceIntegrationTest extends RosTest {
@Override
public void onStart(ConnectedNode connectedNode) {
ServiceServer<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response> serviceServer =
ServiceServer<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceServer =
connectedNode
.newServiceServer(
SERVICE_NAME,
test_ros.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response>() {
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
@Override
public void build(test_ros.AddTwoInts.Request request,
test_ros.AddTwoInts.Response response) throws ServiceException {
public void build(test_ros.AddTwoIntsRequest request,
test_ros.AddTwoIntsResponse response) throws ServiceException {
throw new ServiceException(errorMessage);
}
});
......@@ -158,16 +158,16 @@ public class ServiceIntegrationTest extends RosTest {
@Override
public void onStart(ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response> serviceClient;
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
try {
serviceClient = connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE);
} catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e);
}
test_ros.AddTwoInts.Request request = serviceClient.newMessage();
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoInts.Response>() {
test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
@Override
public void onSuccess(test_ros.AddTwoInts.Response message) {
public void onSuccess(test_ros.AddTwoIntsResponse message) {
fail();
}
......
......@@ -18,7 +18,7 @@ dependencies {
compile 'org.apache.commons:com.springsource.org.apache.commons.codec:1.3.0'
compile 'org.apache.commons:com.springsource.org.apache.commons.lang:2.4.0'
compile 'org.apache.commons:com.springsource.org.apache.commons.io:1.4.0'
compile 'com.google.guava:guava:r07'
compile 'com.google.guava:guava:12.0'
testCompile 'junit:junit:4.8.2'
}
......
......@@ -76,21 +76,7 @@ public class GenerateInterfaces {
for (MessageIdentifier topicType : topicTypes) {
String definition = messageDefinitionProviderChain.get(topicType.getType());
MessageDeclaration messageDeclaration = new MessageDeclaration(topicType, definition);
MessageInterfaceBuilder builder = new MessageInterfaceBuilder();
builder.setMessageDeclaration(messageDeclaration);
builder.setPackageName(messageDeclaration.getPackage());
builder.setInterfaceName(messageDeclaration.getName());
builder.setAddConstantsAndMethods(true);
String content;
try {
content = builder.build(messageFactory);
} catch (Exception e) {
System.out.println(String.format("Failed to generate interface for %s: %s",
topicType.getType(), e.getMessage()));
continue;
}
File file = new File(outputDirectory, topicType.getType() + ".java");
FileUtils.writeStringToFile(file, content);
writeInterface(messageDeclaration, outputDirectory, true);
}
}
......@@ -117,40 +103,34 @@ public class GenerateInterfaces {
}
for (MessageIdentifier serviceType : serviceTypes) {
String definition = messageDefinitionProviderChain.get(serviceType.getType());
MessageInterfaceBuilder builder = new MessageInterfaceBuilder();
builder.setMessageDeclaration(new MessageDeclaration(serviceType, definition));
builder.setPackageName(serviceType.getPackage());
builder.setInterfaceName(serviceType.getName());
builder.setAddConstantsAndMethods(false);
MessageDeclaration serviceDeclaration =
MessageDeclaration.of(serviceType.getType(), definition);
writeInterface(serviceDeclaration, outputDirectory, false);
List<String> requestAndResponse = MessageDefinitionTupleParser.parse(definition, 2);
MessageDeclaration request = new MessageDeclaration(serviceType, requestAndResponse.get(0));
MessageDeclaration response = new MessageDeclaration(serviceType, requestAndResponse.get(1));
MessageInterfaceBuilder requestBuilder = new MessageInterfaceBuilder();
requestBuilder.setMessageDeclaration(request);
requestBuilder.setInterfaceName("Request");
requestBuilder.setAddConstantsAndMethods(true);
MessageInterfaceBuilder responseBuilder = new MessageInterfaceBuilder();
responseBuilder.setMessageDeclaration(response);
responseBuilder.setInterfaceName("Response");
responseBuilder.setAddConstantsAndMethods(true);
MessageDeclaration requestDeclaration =
MessageDeclaration.of(serviceType.getType() + "Request", requestAndResponse.get(0));
MessageDeclaration responseDeclaration =
MessageDeclaration.of(serviceType.getType() + "Response", requestAndResponse.get(1));
writeInterface(requestDeclaration, outputDirectory, true);
writeInterface(responseDeclaration, outputDirectory, true);
}
}
String nestedContent;
private void writeInterface(MessageDeclaration messageDeclaration, File outputDirectory,
boolean addConstantsAndMethods) {
MessageInterfaceBuilder builder = new MessageInterfaceBuilder();
builder.setPackageName(messageDeclaration.getPackage());
builder.setInterfaceName(messageDeclaration.getName());
builder.setMessageDeclaration(messageDeclaration);
builder.setAddConstantsAndMethods(addConstantsAndMethods);
try {
nestedContent =
requestBuilder.build(messageFactory) + "\n" + responseBuilder.build(messageFactory);
String content;
content = builder.build(messageFactory);
File file = new File(outputDirectory, messageDeclaration.getType() + ".java");
FileUtils.writeStringToFile(file, content);
} catch (Exception e) {
System.err.println(String.format("Failed to generate interface for %s: %s",
serviceType.getType(), e.getMessage()));
continue;
}
builder.setNestedContent(nestedContent);
File file = new File(outputDirectory, serviceType.getType() + ".java");
// TODO(damonkohler): Passing in null here is confusing.
FileUtils.writeStringToFile(file, builder.build(null));
System.out.println(String.format("Failed to generate interface for %s: %s",
messageDeclaration.getType(), e.getMessage()));
}
}
......
......@@ -29,7 +29,9 @@ import java.util.List;
*/
public class ServiceDescription extends MessageDeclaration {
private final String requestType;
private final String requestDefinition;
private final String responseType;
private final String responseDefinition;
private final String md5Checksum;
......@@ -37,6 +39,8 @@ public class ServiceDescription extends MessageDeclaration {
super(MessageIdentifier.of(type), definition);
this.md5Checksum = md5Checksum;
List<String> requestAndResponse = MessageDefinitionTupleParser.parse(definition, 2);
requestType = type + "Request";
responseType = type + "Response";
requestDefinition = requestAndResponse.get(0);
responseDefinition = requestAndResponse.get(1);
}
......@@ -45,10 +49,18 @@ public class ServiceDescription extends MessageDeclaration {
return md5Checksum;
}
public String getRequestType() {
return requestType;
}
public String getRequestDefinition() {
return requestDefinition;
}
public String getResponseType() {
return responseType;
}
public String getResponseDefinition() {
return responseDefinition;
}
......
......@@ -17,6 +17,7 @@
package org.ros.internal.message.service;
import org.ros.internal.message.DefaultMessageFactory;
import org.ros.internal.message.DefaultMessageInterfaceClassProvider;
import org.ros.internal.message.MessageProxyFactory;
import org.ros.message.MessageDefinitionProvider;
import org.ros.message.MessageFactory;
......@@ -34,13 +35,13 @@ public class ServiceRequestMessageFactory implements MessageFactory {
serviceDescriptionFactory = new ServiceDescriptionFactory(messageDefinitionProvider);
messageFactory = new DefaultMessageFactory(messageDefinitionProvider);
messageProxyFactory =
new MessageProxyFactory(new ServiceRequestMessageInterfaceClassProvider(), messageFactory);
new MessageProxyFactory(new DefaultMessageInterfaceClassProvider(), messageFactory);
}
@Override
public <T> T newFromType(String serviceType) {
ServiceDescription serviceDescription = serviceDescriptionFactory.newFromType(serviceType);
return messageProxyFactory.newMessageProxy(serviceType,
return messageProxyFactory.newMessageProxy(serviceDescription.getRequestType(),
serviceDescription.getRequestDefinition());
}
}
......@@ -17,6 +17,7 @@
package org.ros.internal.message.service;
import org.ros.internal.message.DefaultMessageFactory;
import org.ros.internal.message.DefaultMessageInterfaceClassProvider;
import org.ros.internal.message.MessageProxyFactory;
import org.ros.message.MessageDefinitionProvider;
import org.ros.message.MessageFactory;
......@@ -34,13 +35,13 @@ public class ServiceResponseMessageFactory implements MessageFactory {
serviceDescriptionFactory = new ServiceDescriptionFactory(messageDefinitionProvider);
messageFactory = new DefaultMessageFactory(messageDefinitionProvider);
messageProxyFactory =
new MessageProxyFactory(new ServiceResponseMessageInterfaceClassProvider(), messageFactory);
new MessageProxyFactory(new DefaultMessageInterfaceClassProvider(), messageFactory);
}
@Override
public <T> T newFromType(String serviceType) {
ServiceDescription serviceDescription = serviceDescriptionFactory.newFromType(serviceType);
return messageProxyFactory.newMessageProxy(serviceType,
return messageProxyFactory.newMessageProxy(serviceDescription.getResponseType(),
serviceDescription.getResponseDefinition());
}
}
......@@ -40,18 +40,18 @@ public class Client extends AbstractNodeMain {
@Override
public void onStart(final ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response> serviceClient;
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
try {
serviceClient = connectedNode.newServiceClient("add_two_ints", test_ros.AddTwoInts._TYPE);
} catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e);
}
final test_ros.AddTwoInts.Request request = serviceClient.newMessage();
final test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
request.setA(2);
request.setB(2);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoInts.Response>() {
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
@Override
public void onSuccess(test_ros.AddTwoInts.Response response) {
public void onSuccess(test_ros.AddTwoIntsResponse response) {
connectedNode.getLog().info(
String.format("%d + %d = %d", request.getA(), request.getB(), response.getSum()));
}
......
......@@ -38,10 +38,10 @@ public class Server extends AbstractNodeMain {
@Override
public void onStart(ConnectedNode connectedNode) {
connectedNode.newServiceServer("add_two_ints", test_ros.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response>() {
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
@Override
public void build(test_ros.AddTwoInts.Request request,
test_ros.AddTwoInts.Response response) {
public void
build(test_ros.AddTwoIntsRequest request, test_ros.AddTwoIntsResponse response) {
response.setSum(request.getA() + request.getB());
}
});
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment