Skip to content
Snippets Groups Projects
Commit 560b9b0b authored by Daniel Stonier's avatar Daniel Stonier
Browse files

test_ros -> rosjava_test_msgs

parent 206655a4
No related branches found
No related tags found
No related merge requests found
Showing
with 81 additions and 80 deletions
cmake_minimum_required(VERSION 2.8.3) cmake_minimum_required(VERSION 2.8.3)
project(rosjava_core) project(rosjava_core)
find_package(catkin REQUIRED rosjava_tools) find_package(catkin REQUIRED rosjava_build_tools)
catkin_rosjava_setup(uploadArchives) catkin_rosjava_setup(uploadArchives)
......
...@@ -241,7 +241,7 @@ Services ...@@ -241,7 +241,7 @@ Services
The following class (:javadoc:`org.ros.rosjava_tutorial_services.Server`) is The following class (:javadoc:`org.ros.rosjava_tutorial_services.Server`) is
available from the rosjava_tutorial_services package. In this example, we available from the rosjava_tutorial_services package. In this example, we
create a :javadoc:`org.ros.node.service.ServiceServer` for the create a :javadoc:`org.ros.node.service.ServiceServer` for the
``test_ros.AddTwoInts`` service. This should feel relatively familiar if you're ``rosjava_test_msgs.AddTwoInts`` service. This should feel relatively familiar if you're
a ROS veteran. a ROS veteran.
.. literalinclude:: ../../../../rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java .. literalinclude:: ../../../../rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java
......
...@@ -18,7 +18,8 @@ dependencies { ...@@ -18,7 +18,8 @@ dependencies {
compile project(':apache_xmlrpc_common') compile project(':apache_xmlrpc_common')
compile project(':apache_xmlrpc_server') compile project(':apache_xmlrpc_server')
compile project(':apache_xmlrpc_client') compile project(':apache_xmlrpc_client')
compile 'org.ros.rosjava_bootstrap:message_generator:0.1.+' compile 'org.ros.rosjava_bootstrap:message_generation:0.1.+'
compile 'org.ros.rosjava_messages:rosjava_test_msgs:0.1.+'
compile 'org.ros.rosjava_messages:rosgraph_msgs:1.9.+' compile 'org.ros.rosjava_messages:rosgraph_msgs:1.9.+'
compile 'org.ros.rosjava_messages:geometry_msgs:1.10.+' compile 'org.ros.rosjava_messages:geometry_msgs:1.10.+'
compile 'org.ros.rosjava_messages:nav_msgs:1.10.+' compile 'org.ros.rosjava_messages:nav_msgs:1.10.+'
......
...@@ -93,7 +93,7 @@ public interface ConnectedNode extends Node { ...@@ -93,7 +93,7 @@ public interface ConnectedNode extends Node {
* @param serviceName * @param serviceName
* the name of the service * the name of the service
* @param serviceType * @param serviceType
* the type of the service (e.g. "test_ros/AddTwoInts") * the type of the service (e.g. "rosjava_test_msgs/AddTwoInts")
* @param serviceResponseBuilder * @param serviceResponseBuilder
* called for every request to build a response * called for every request to build a response
* @return a {@link ServiceServer} * @return a {@link ServiceServer}
...@@ -139,7 +139,7 @@ public interface ConnectedNode extends Node { ...@@ -139,7 +139,7 @@ public interface ConnectedNode extends Node {
* @param serviceName * @param serviceName
* the name of the service * the name of the service
* @param serviceType * @param serviceType
* the type of the service (e.g. "test_ros/AddTwoInts") * the type of the service (e.g. "rosjava_test_msgs/AddTwoInts")
* @return a {@link ServiceClient} * @return a {@link ServiceClient}
* @throws ServiceNotFoundException * @throws ServiceNotFoundException
* thrown if no matching service could be found * thrown if no matching service could be found
......
...@@ -43,7 +43,7 @@ public class ServiceIntegrationTest extends RosTest { ...@@ -43,7 +43,7 @@ public class ServiceIntegrationTest extends RosTest {
@Test @Test
public void testPesistentServiceConnection() throws Exception { public void testPesistentServiceConnection() throws Exception {
final CountDownServiceServerListener<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> countDownServiceServerListener = final CountDownServiceServerListener<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> countDownServiceServerListener =
CountDownServiceServerListener.newDefault(); CountDownServiceServerListener.newDefault();
nodeMainExecutor.execute(new AbstractNodeMain() { nodeMainExecutor.execute(new AbstractNodeMain() {
@Override @Override
...@@ -53,20 +53,20 @@ public class ServiceIntegrationTest extends RosTest { ...@@ -53,20 +53,20 @@ public class ServiceIntegrationTest extends RosTest {
@Override @Override
public void onStart(final ConnectedNode connectedNode) { public void onStart(final ConnectedNode connectedNode) {
ServiceServer<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceServer = ServiceServer<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceServer =
connectedNode connectedNode
.newServiceServer( .newServiceServer(
SERVICE_NAME, SERVICE_NAME,
test_ros.AddTwoInts._TYPE, rosjava_test_msgs.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() { new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
@Override @Override
public void build(test_ros.AddTwoIntsRequest request, public void build(rosjava_test_msgs.AddTwoIntsRequest request,
test_ros.AddTwoIntsResponse response) { rosjava_test_msgs.AddTwoIntsResponse response) {
response.setSum(request.getA() + request.getB()); response.setSum(request.getA() + request.getB());
} }
}); });
try { try {
connectedNode.newServiceServer(SERVICE_NAME, test_ros.AddTwoInts._TYPE, null); connectedNode.newServiceServer(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE, null);
fail(); fail();
} catch (DuplicateServiceException e) { } catch (DuplicateServiceException e) {
// Only one ServiceServer with a given name can be created. // Only one ServiceServer with a given name can be created.
...@@ -86,23 +86,23 @@ public class ServiceIntegrationTest extends RosTest { ...@@ -86,23 +86,23 @@ public class ServiceIntegrationTest extends RosTest {
@Override @Override
public void onStart(ConnectedNode connectedNode) { public void onStart(ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient; ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
try { try {
serviceClient = connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE); serviceClient = connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
// Test that requesting another client for the same service returns // Test that requesting another client for the same service returns
// the same instance. // the same instance.
ServiceClient<?, ?> duplicate = ServiceClient<?, ?> duplicate =
connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE); connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
assertEquals(serviceClient, duplicate); assertEquals(serviceClient, duplicate);
} catch (ServiceNotFoundException e) { } catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e); throw new RosRuntimeException(e);
} }
test_ros.AddTwoIntsRequest request = serviceClient.newMessage(); rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
request.setA(2); request.setA(2);
request.setB(2); request.setB(2);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() { serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override @Override
public void onSuccess(test_ros.AddTwoIntsResponse response) { public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
assertEquals(response.getSum(), 4); assertEquals(response.getSum(), 4);
latch.countDown(); latch.countDown();
} }
...@@ -116,9 +116,9 @@ public class ServiceIntegrationTest extends RosTest { ...@@ -116,9 +116,9 @@ public class ServiceIntegrationTest extends RosTest {
// Regression test for issue 122. // Regression test for issue 122.
request.setA(3); request.setA(3);
request.setB(3); request.setB(3);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() { serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override @Override
public void onSuccess(test_ros.AddTwoIntsResponse response) { public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
assertEquals(response.getSum(), 6); assertEquals(response.getSum(), 6);
latch.countDown(); latch.countDown();
} }
...@@ -137,7 +137,7 @@ public class ServiceIntegrationTest extends RosTest { ...@@ -137,7 +137,7 @@ public class ServiceIntegrationTest extends RosTest {
@Test @Test
public void testRequestFailure() throws Exception { public void testRequestFailure() throws Exception {
final String errorMessage = "Error!"; final String errorMessage = "Error!";
final CountDownServiceServerListener<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> countDownServiceServerListener = final CountDownServiceServerListener<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> countDownServiceServerListener =
CountDownServiceServerListener.newDefault(); CountDownServiceServerListener.newDefault();
nodeMainExecutor.execute(new AbstractNodeMain() { nodeMainExecutor.execute(new AbstractNodeMain() {
@Override @Override
...@@ -147,15 +147,15 @@ public class ServiceIntegrationTest extends RosTest { ...@@ -147,15 +147,15 @@ public class ServiceIntegrationTest extends RosTest {
@Override @Override
public void onStart(ConnectedNode connectedNode) { public void onStart(ConnectedNode connectedNode) {
ServiceServer<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceServer = ServiceServer<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceServer =
connectedNode connectedNode
.newServiceServer( .newServiceServer(
SERVICE_NAME, SERVICE_NAME,
test_ros.AddTwoInts._TYPE, rosjava_test_msgs.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() { new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
@Override @Override
public void build(test_ros.AddTwoIntsRequest request, public void build(rosjava_test_msgs.AddTwoIntsRequest request,
test_ros.AddTwoIntsResponse response) throws ServiceException { rosjava_test_msgs.AddTwoIntsResponse response) throws ServiceException {
throw new ServiceException(errorMessage); throw new ServiceException(errorMessage);
} }
}); });
...@@ -174,16 +174,16 @@ public class ServiceIntegrationTest extends RosTest { ...@@ -174,16 +174,16 @@ public class ServiceIntegrationTest extends RosTest {
@Override @Override
public void onStart(ConnectedNode connectedNode) { public void onStart(ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient; ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
try { try {
serviceClient = connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE); serviceClient = connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
} catch (ServiceNotFoundException e) { } catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e); throw new RosRuntimeException(e);
} }
test_ros.AddTwoIntsRequest request = serviceClient.newMessage(); rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() { serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override @Override
public void onSuccess(test_ros.AddTwoIntsResponse message) { public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse message) {
fail(); fail();
} }
......
...@@ -175,13 +175,13 @@ public class TopicIntegrationTest extends RosTest { ...@@ -175,13 +175,13 @@ public class TopicIntegrationTest extends RosTest {
}, nodeConfiguration); }, nodeConfiguration);
} }
private final class Listener implements MessageListener<test_ros.TestHeader> { private final class Listener implements MessageListener<rosjava_test_msgs.TestHeader> {
private final CountDownLatch latch = new CountDownLatch(10); private final CountDownLatch latch = new CountDownLatch(10);
private test_ros.TestHeader lastMessage; private rosjava_test_msgs.TestHeader lastMessage;
@Override @Override
public void onNewMessage(test_ros.TestHeader message) { public void onNewMessage(rosjava_test_msgs.TestHeader message) {
int seq = message.getHeader().getSeq(); int seq = message.getHeader().getSeq();
long stamp = message.getHeader().getStamp().totalNsecs(); long stamp = message.getHeader().getStamp().totalNsecs();
if (lastMessage != null) { if (lastMessage != null) {
...@@ -210,13 +210,13 @@ public class TopicIntegrationTest extends RosTest { ...@@ -210,13 +210,13 @@ public class TopicIntegrationTest extends RosTest {
@Override @Override
public void onStart(final ConnectedNode connectedNode) { public void onStart(final ConnectedNode connectedNode) {
final Publisher<test_ros.TestHeader> publisher = final Publisher<rosjava_test_msgs.TestHeader> publisher =
connectedNode.newPublisher("foo", test_ros.TestHeader._TYPE); connectedNode.newPublisher("foo", rosjava_test_msgs.TestHeader._TYPE);
connectedNode.executeCancellableLoop(new CancellableLoop() { connectedNode.executeCancellableLoop(new CancellableLoop() {
@Override @Override
public void loop() throws InterruptedException { public void loop() throws InterruptedException {
test_ros.TestHeader message = rosjava_test_msgs.TestHeader message =
connectedNode.getTopicMessageFactory().newFromType(test_ros.TestHeader._TYPE); connectedNode.getTopicMessageFactory().newFromType(rosjava_test_msgs.TestHeader._TYPE);
message.getHeader().setStamp(connectedNode.getCurrentTime()); message.getHeader().setStamp(connectedNode.getCurrentTime());
publisher.publish(message); publisher.publish(message);
// There needs to be some time between messages in order to // There needs to be some time between messages in order to
...@@ -236,8 +236,8 @@ public class TopicIntegrationTest extends RosTest { ...@@ -236,8 +236,8 @@ public class TopicIntegrationTest extends RosTest {
@Override @Override
public void onStart(ConnectedNode connectedNode) { public void onStart(ConnectedNode connectedNode) {
Subscriber<test_ros.TestHeader> subscriber = Subscriber<rosjava_test_msgs.TestHeader> subscriber =
connectedNode.newSubscriber("foo", test_ros.TestHeader._TYPE); connectedNode.newSubscriber("foo", rosjava_test_msgs.TestHeader._TYPE);
subscriber.addMessageListener(listener, QUEUE_CAPACITY); subscriber.addMessageListener(listener, QUEUE_CAPACITY);
} }
}, nodeConfiguration); }, nodeConfiguration);
......
#!/usr/bin/env python #!/usr/bin/env python
from ros import rospy from ros import rospy
from ros import test_ros from ros import rosjava_test_msgs
import test_ros.msg import rosjava_test_msgs.msg
import random import random
def publisher(): def publisher():
rospy.init_node('composite_publisher') rospy.init_node('composite_publisher')
pub = rospy.Publisher('composite_in', test_ros.msg.Composite) pub = rospy.Publisher('composite_in', rosjava_test_msgs.msg.Composite)
r = rospy.Rate(10) r = rospy.Rate(10)
m = test_ros.msg.Composite() m = rosjava_test_msgs.msg.Composite()
m.a.x = random.random() * 10000. m.a.x = random.random() * 10000.
m.a.y = random.random() * 10000. m.a.y = random.random() * 10000.
m.a.z = random.random() * 10000. m.a.z = random.random() * 10000.
......
...@@ -38,14 +38,14 @@ NAME = 'composite_passthrough' ...@@ -38,14 +38,14 @@ NAME = 'composite_passthrough'
import roslib; roslib.load_manifest(PKG) import roslib; roslib.load_manifest(PKG)
from ros import rospy from ros import rospy
from ros import test_ros from ros import rosjava_test_msgs
from ros import rostest from ros import rostest
import sys import sys
import time import time
import unittest import unittest
from test_ros.msg import Composite from rosjava_test_msgs.msg import Composite
class CompositePassthrough(unittest.TestCase): class CompositePassthrough(unittest.TestCase):
......
...@@ -48,7 +48,7 @@ import time ...@@ -48,7 +48,7 @@ import time
import unittest import unittest
from std_msgs.msg import String, Bool, Int64, Float64 from std_msgs.msg import String, Bool, Int64, Float64
from test_ros.msg import Composite, CompositeA, CompositeB, TestArrays from rosjava_test_msgs.msg import Composite, CompositeA, CompositeB, TestArrays
class TestParameterClient(unittest.TestCase): class TestParameterClient(unittest.TestCase):
......
...@@ -38,14 +38,14 @@ NAME = 'testheader_passthrough' ...@@ -38,14 +38,14 @@ NAME = 'testheader_passthrough'
import roslib; roslib.load_manifest(PKG) import roslib; roslib.load_manifest(PKG)
from ros import rospy from ros import rospy
from ros import test_ros from ros import rosjava_test_msgs
from ros import rostest from ros import rostest
import sys import sys
import time import time
import unittest import unittest
from test_ros.msg import TestHeader from rosjava_test_msgs.msg import TestHeader
class TestHeaderPassthrough(unittest.TestCase): class TestHeaderPassthrough(unittest.TestCase):
......
#!/usr/bin/env python #!/usr/bin/env python
from ros import rospy from ros import rospy
from ros import test_ros from ros import rosjava_test_msgs
import test_ros.msg import rosjava_test_msgs.msg
def publisher(): def publisher():
rospy.init_node('testheader_publisher') rospy.init_node('testheader_publisher')
pub = rospy.Publisher('test_header_in', test_ros.msg.TestHeader) pub = rospy.Publisher('test_header_in', rosjava_test_msgs.msg.TestHeader)
r = rospy.Rate(10) r = rospy.Rate(10)
m = test_ros.msg.TestHeader() m = rosjava_test_msgs.msg.TestHeader()
m.caller_id = rospy.get_name() m.caller_id = rospy.get_name()
m.header.stamp = rospy.get_rostime() m.header.stamp = rospy.get_rostime()
while not rospy.is_shutdown(): while not rospy.is_shutdown():
......
...@@ -55,10 +55,10 @@ public class ParameterServerTestNode extends AbstractNodeMain { ...@@ -55,10 +55,10 @@ public class ParameterServerTestNode extends AbstractNodeMain {
connectedNode.newPublisher("bool", std_msgs.Bool._TYPE); connectedNode.newPublisher("bool", std_msgs.Bool._TYPE);
final Publisher<std_msgs.Float64> pub_float = final Publisher<std_msgs.Float64> pub_float =
connectedNode.newPublisher("float", std_msgs.Float64._TYPE); connectedNode.newPublisher("float", std_msgs.Float64._TYPE);
final Publisher<test_ros.Composite> pub_composite = final Publisher<rosjava_test_msgs.Composite> pub_composite =
connectedNode.newPublisher("composite", test_ros.Composite._TYPE); connectedNode.newPublisher("composite", rosjava_test_msgs.Composite._TYPE);
final Publisher<test_ros.TestArrays> pub_list = final Publisher<rosjava_test_msgs.TestArrays> pub_list =
connectedNode.newPublisher("list", test_ros.TestArrays._TYPE); connectedNode.newPublisher("list", rosjava_test_msgs.TestArrays._TYPE);
ParameterTree param = connectedNode.getParameterTree(); ParameterTree param = connectedNode.getParameterTree();
...@@ -90,8 +90,8 @@ public class ParameterServerTestNode extends AbstractNodeMain { ...@@ -90,8 +90,8 @@ public class ParameterServerTestNode extends AbstractNodeMain {
float_m.setData(param.getDouble(resolver.resolve("float"))); float_m.setData(param.getDouble(resolver.resolve("float")));
log.info("float: " + float_m.getData()); log.info("float: " + float_m.getData());
final test_ros.Composite composite_m = final rosjava_test_msgs.Composite composite_m =
topicMessageFactory.newFromType(test_ros.Composite._TYPE); topicMessageFactory.newFromType(rosjava_test_msgs.Composite._TYPE);
Map composite_map = param.getMap(resolver.resolve("composite")); Map composite_map = param.getMap(resolver.resolve("composite"));
composite_m.getA().setW((Double) ((Map) composite_map.get("a")).get("w")); composite_m.getA().setW((Double) ((Map) composite_map.get("a")).get("w"));
composite_m.getA().setX((Double) ((Map) composite_map.get("a")).get("x")); composite_m.getA().setX((Double) ((Map) composite_map.get("a")).get("x"));
...@@ -101,7 +101,7 @@ public class ParameterServerTestNode extends AbstractNodeMain { ...@@ -101,7 +101,7 @@ public class ParameterServerTestNode extends AbstractNodeMain {
composite_m.getB().setY((Double) ((Map) composite_map.get("b")).get("y")); composite_m.getB().setY((Double) ((Map) composite_map.get("b")).get("y"));
composite_m.getB().setZ((Double) ((Map) composite_map.get("b")).get("z")); composite_m.getB().setZ((Double) ((Map) composite_map.get("b")).get("z"));
final test_ros.TestArrays list_m = topicMessageFactory.newFromType(test_ros.TestArrays._TYPE); final rosjava_test_msgs.TestArrays list_m = topicMessageFactory.newFromType(rosjava_test_msgs.TestArrays._TYPE);
// only using the integer part for easier (non-float) comparison // only using the integer part for easier (non-float) comparison
@SuppressWarnings("unchecked") @SuppressWarnings("unchecked")
List<Integer> list = (List<Integer>) param.getList(resolver.resolve("list")); List<Integer> list = (List<Integer>) param.getList(resolver.resolve("list"));
......
...@@ -67,31 +67,31 @@ public class PassthroughTestNode extends AbstractNodeMain { ...@@ -67,31 +67,31 @@ public class PassthroughTestNode extends AbstractNodeMain {
int64Subscriber.addMessageListener(int64_cb); int64Subscriber.addMessageListener(int64_cb);
// TestHeader pass through // TestHeader pass through
final Publisher<test_ros.TestHeader> pub_header = final Publisher<rosjava_test_msgs.TestHeader> pub_header =
connectedNode.newPublisher("test_header_out", test_ros.TestHeader._TYPE); connectedNode.newPublisher("test_header_out", rosjava_test_msgs.TestHeader._TYPE);
MessageListener<test_ros.TestHeader> header_cb = new MessageListener<test_ros.TestHeader>() { MessageListener<rosjava_test_msgs.TestHeader> header_cb = new MessageListener<rosjava_test_msgs.TestHeader>() {
@Override @Override
public void onNewMessage(test_ros.TestHeader m) { public void onNewMessage(rosjava_test_msgs.TestHeader m) {
m.setOrigCallerId(m.getCallerId()); m.setOrigCallerId(m.getCallerId());
m.setCallerId(connectedNode.getName().toString()); m.setCallerId(connectedNode.getName().toString());
pub_header.publish(m); pub_header.publish(m);
} }
}; };
Subscriber<test_ros.TestHeader> testHeaderSubscriber = Subscriber<rosjava_test_msgs.TestHeader> testHeaderSubscriber =
connectedNode.newSubscriber("test_header_in", "test_ros/TestHeader"); connectedNode.newSubscriber("test_header_in", "rosjava_test_msgs/TestHeader");
testHeaderSubscriber.addMessageListener(header_cb); testHeaderSubscriber.addMessageListener(header_cb);
// TestComposite pass through // TestComposite pass through
final Publisher<test_ros.Composite> pub_composite = final Publisher<rosjava_test_msgs.Composite> pub_composite =
connectedNode.newPublisher("composite_out", "test_ros/Composite"); connectedNode.newPublisher("composite_out", "rosjava_test_msgs/Composite");
MessageListener<test_ros.Composite> composite_cb = new MessageListener<test_ros.Composite>() { MessageListener<rosjava_test_msgs.Composite> composite_cb = new MessageListener<rosjava_test_msgs.Composite>() {
@Override @Override
public void onNewMessage(test_ros.Composite m) { public void onNewMessage(rosjava_test_msgs.Composite m) {
pub_composite.publish(m); pub_composite.publish(m);
} }
}; };
Subscriber<test_ros.Composite> compositeSubscriber = Subscriber<rosjava_test_msgs.Composite> compositeSubscriber =
connectedNode.newSubscriber("composite_in", "test_ros/Composite"); connectedNode.newSubscriber("composite_in", "rosjava_test_msgs/Composite");
compositeSubscriber.addMessageListener(composite_cb); compositeSubscriber.addMessageListener(composite_cb);
} }
} }
...@@ -40,18 +40,18 @@ public class Client extends AbstractNodeMain { ...@@ -40,18 +40,18 @@ public class Client extends AbstractNodeMain {
@Override @Override
public void onStart(final ConnectedNode connectedNode) { public void onStart(final ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient; ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
try { try {
serviceClient = connectedNode.newServiceClient("add_two_ints", test_ros.AddTwoInts._TYPE); serviceClient = connectedNode.newServiceClient("add_two_ints", rosjava_test_msgs.AddTwoInts._TYPE);
} catch (ServiceNotFoundException e) { } catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e); throw new RosRuntimeException(e);
} }
final test_ros.AddTwoIntsRequest request = serviceClient.newMessage(); final rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
request.setA(2); request.setA(2);
request.setB(2); request.setB(2);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() { serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override @Override
public void onSuccess(test_ros.AddTwoIntsResponse response) { public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
connectedNode.getLog().info( connectedNode.getLog().info(
String.format("%d + %d = %d", request.getA(), request.getB(), response.getSum())); String.format("%d + %d = %d", request.getA(), request.getB(), response.getSum()));
} }
......
...@@ -37,11 +37,11 @@ public class Server extends AbstractNodeMain { ...@@ -37,11 +37,11 @@ public class Server extends AbstractNodeMain {
@Override @Override
public void onStart(ConnectedNode connectedNode) { public void onStart(ConnectedNode connectedNode) {
connectedNode.newServiceServer("add_two_ints", test_ros.AddTwoInts._TYPE, connectedNode.newServiceServer("add_two_ints", rosjava_test_msgs.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() { new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
@Override @Override
public void public void
build(test_ros.AddTwoIntsRequest request, test_ros.AddTwoIntsResponse response) { build(rosjava_test_msgs.AddTwoIntsRequest request, rosjava_test_msgs.AddTwoIntsResponse response) {
response.setSum(request.getA() + request.getB()); 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