Skip to content

Commit

Permalink
test_ros -> rosjava_test_msgs
Browse files Browse the repository at this point in the history
  • Loading branch information
stonier committed Sep 12, 2013
1 parent 206655a commit 560b9b0
Show file tree
Hide file tree
Showing 15 changed files with 81 additions and 80 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 2.8.3)
project(rosjava_core)

find_package(catkin REQUIRED rosjava_tools)
find_package(catkin REQUIRED rosjava_build_tools)

catkin_rosjava_setup(uploadArchives)

Expand Down
2 changes: 1 addition & 1 deletion docs/src/main/sphinx/getting_started.rst
Original file line number Diff line number Diff line change
Expand Up @@ -241,7 +241,7 @@ Services
The following class (:javadoc:`org.ros.rosjava_tutorial_services.Server`) is
available from the rosjava_tutorial_services package. In this example, we
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.

.. literalinclude:: ../../../../rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java
Expand Down
3 changes: 2 additions & 1 deletion rosjava/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,8 @@ dependencies {
compile project(':apache_xmlrpc_common')
compile project(':apache_xmlrpc_server')
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:geometry_msgs:1.10.+'
compile 'org.ros.rosjava_messages:nav_msgs:1.10.+'
Expand Down
4 changes: 2 additions & 2 deletions rosjava/src/main/java/org/ros/node/ConnectedNode.java
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ public interface ConnectedNode extends Node {
* @param serviceName
* the name of the service
* @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
* called for every request to build a response
* @return a {@link ServiceServer}
Expand Down Expand Up @@ -139,7 +139,7 @@ <T, S> ServiceServer<T, S> newServiceServer(String serviceName, String serviceTy
* @param serviceName
* the name of the service
* @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}
* @throws ServiceNotFoundException
* thrown if no matching service could be found
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ public class ServiceIntegrationTest extends RosTest {

@Test
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();
nodeMainExecutor.execute(new AbstractNodeMain() {
@Override
Expand All @@ -53,20 +53,20 @@ public GraphName getDefaultNodeName() {

@Override
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
.newServiceServer(
SERVICE_NAME,
test_ros.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
rosjava_test_msgs.AddTwoInts._TYPE,
new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
@Override
public void build(test_ros.AddTwoIntsRequest request,
test_ros.AddTwoIntsResponse response) {
public void build(rosjava_test_msgs.AddTwoIntsRequest request,
rosjava_test_msgs.AddTwoIntsResponse response) {
response.setSum(request.getA() + request.getB());
}
});
try {
connectedNode.newServiceServer(SERVICE_NAME, test_ros.AddTwoInts._TYPE, null);
connectedNode.newServiceServer(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE, null);
fail();
} catch (DuplicateServiceException e) {
// Only one ServiceServer with a given name can be created.
Expand All @@ -86,23 +86,23 @@ public GraphName getDefaultNodeName() {

@Override
public void onStart(ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
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
// the same instance.
ServiceClient<?, ?> duplicate =
connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE);
connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
assertEquals(serviceClient, duplicate);
} catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e);
}
test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
request.setA(2);
request.setB(2);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override
public void onSuccess(test_ros.AddTwoIntsResponse response) {
public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
assertEquals(response.getSum(), 4);
latch.countDown();
}
Expand All @@ -116,9 +116,9 @@ public void onFailure(RemoteException e) {
// Regression test for issue 122.
request.setA(3);
request.setB(3);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override
public void onSuccess(test_ros.AddTwoIntsResponse response) {
public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
assertEquals(response.getSum(), 6);
latch.countDown();
}
Expand All @@ -137,7 +137,7 @@ public void onFailure(RemoteException e) {
@Test
public void testRequestFailure() throws Exception {
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();
nodeMainExecutor.execute(new AbstractNodeMain() {
@Override
Expand All @@ -147,15 +147,15 @@ public GraphName getDefaultNodeName() {

@Override
public void onStart(ConnectedNode connectedNode) {
ServiceServer<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceServer =
ServiceServer<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceServer =
connectedNode
.newServiceServer(
SERVICE_NAME,
test_ros.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse>() {
rosjava_test_msgs.AddTwoInts._TYPE,
new ServiceResponseBuilder<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse>() {
@Override
public void build(test_ros.AddTwoIntsRequest request,
test_ros.AddTwoIntsResponse response) throws ServiceException {
public void build(rosjava_test_msgs.AddTwoIntsRequest request,
rosjava_test_msgs.AddTwoIntsResponse response) throws ServiceException {
throw new ServiceException(errorMessage);
}
});
Expand All @@ -174,16 +174,16 @@ public GraphName getDefaultNodeName() {

@Override
public void onStart(ConnectedNode connectedNode) {
ServiceClient<test_ros.AddTwoIntsRequest, test_ros.AddTwoIntsResponse> serviceClient;
ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
try {
serviceClient = connectedNode.newServiceClient(SERVICE_NAME, test_ros.AddTwoInts._TYPE);
serviceClient = connectedNode.newServiceClient(SERVICE_NAME, rosjava_test_msgs.AddTwoInts._TYPE);
} catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e);
}
test_ros.AddTwoIntsRequest request = serviceClient.newMessage();
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoIntsResponse>() {
rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override
public void onSuccess(test_ros.AddTwoIntsResponse message) {
public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse message) {
fail();
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,13 +175,13 @@ public void onStart(ConnectedNode connectedNode) {
}, 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 test_ros.TestHeader lastMessage;
private rosjava_test_msgs.TestHeader lastMessage;

@Override
public void onNewMessage(test_ros.TestHeader message) {
public void onNewMessage(rosjava_test_msgs.TestHeader message) {
int seq = message.getHeader().getSeq();
long stamp = message.getHeader().getStamp().totalNsecs();
if (lastMessage != null) {
Expand Down Expand Up @@ -210,13 +210,13 @@ public GraphName getDefaultNodeName() {

@Override
public void onStart(final ConnectedNode connectedNode) {
final Publisher<test_ros.TestHeader> publisher =
connectedNode.newPublisher("foo", test_ros.TestHeader._TYPE);
final Publisher<rosjava_test_msgs.TestHeader> publisher =
connectedNode.newPublisher("foo", rosjava_test_msgs.TestHeader._TYPE);
connectedNode.executeCancellableLoop(new CancellableLoop() {
@Override
public void loop() throws InterruptedException {
test_ros.TestHeader message =
connectedNode.getTopicMessageFactory().newFromType(test_ros.TestHeader._TYPE);
rosjava_test_msgs.TestHeader message =
connectedNode.getTopicMessageFactory().newFromType(rosjava_test_msgs.TestHeader._TYPE);
message.getHeader().setStamp(connectedNode.getCurrentTime());
publisher.publish(message);
// There needs to be some time between messages in order to
Expand All @@ -236,8 +236,8 @@ public GraphName getDefaultNodeName() {

@Override
public void onStart(ConnectedNode connectedNode) {
Subscriber<test_ros.TestHeader> subscriber =
connectedNode.newSubscriber("foo", test_ros.TestHeader._TYPE);
Subscriber<rosjava_test_msgs.TestHeader> subscriber =
connectedNode.newSubscriber("foo", rosjava_test_msgs.TestHeader._TYPE);
subscriber.addMessageListener(listener, QUEUE_CAPACITY);
}
}, nodeConfiguration);
Expand Down
8 changes: 4 additions & 4 deletions rosjava/test/composite_publisher.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
#!/usr/bin/env python
from ros import rospy
from ros import test_ros
import test_ros.msg
from ros import rosjava_test_msgs
import rosjava_test_msgs.msg
import random

def 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)
m = test_ros.msg.Composite()
m = rosjava_test_msgs.msg.Composite()
m.a.x = random.random() * 10000.
m.a.y = random.random() * 10000.
m.a.z = random.random() * 10000.
Expand Down
4 changes: 2 additions & 2 deletions rosjava/test/test_composite_passthrough.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,14 @@
import roslib; roslib.load_manifest(PKG)

from ros import rospy
from ros import test_ros
from ros import rosjava_test_msgs
from ros import rostest

import sys
import time
import unittest

from test_ros.msg import Composite
from rosjava_test_msgs.msg import Composite

class CompositePassthrough(unittest.TestCase):

Expand Down
2 changes: 1 addition & 1 deletion rosjava/test/test_parameter_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@
import unittest

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):

Expand Down
4 changes: 2 additions & 2 deletions rosjava/test/test_testheader_passthrough.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,14 @@
import roslib; roslib.load_manifest(PKG)

from ros import rospy
from ros import test_ros
from ros import rosjava_test_msgs
from ros import rostest

import sys
import time
import unittest

from test_ros.msg import TestHeader
from rosjava_test_msgs.msg import TestHeader

class TestHeaderPassthrough(unittest.TestCase):

Expand Down
8 changes: 4 additions & 4 deletions rosjava/test/testheader_publisher.py
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
#!/usr/bin/env python
from ros import rospy
from ros import test_ros
import test_ros.msg
from ros import rosjava_test_msgs
import rosjava_test_msgs.msg

def 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)
m = test_ros.msg.TestHeader()
m = rosjava_test_msgs.msg.TestHeader()
m.caller_id = rospy.get_name()
m.header.stamp = rospy.get_rostime()
while not rospy.is_shutdown():
Expand Down
14 changes: 7 additions & 7 deletions rosjava_test/src/main/java/org/ros/ParameterServerTestNode.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,10 @@ public void onStart(ConnectedNode connectedNode) {
connectedNode.newPublisher("bool", std_msgs.Bool._TYPE);
final Publisher<std_msgs.Float64> pub_float =
connectedNode.newPublisher("float", std_msgs.Float64._TYPE);
final Publisher<test_ros.Composite> pub_composite =
connectedNode.newPublisher("composite", test_ros.Composite._TYPE);
final Publisher<test_ros.TestArrays> pub_list =
connectedNode.newPublisher("list", test_ros.TestArrays._TYPE);
final Publisher<rosjava_test_msgs.Composite> pub_composite =
connectedNode.newPublisher("composite", rosjava_test_msgs.Composite._TYPE);
final Publisher<rosjava_test_msgs.TestArrays> pub_list =
connectedNode.newPublisher("list", rosjava_test_msgs.TestArrays._TYPE);

ParameterTree param = connectedNode.getParameterTree();

Expand Down Expand Up @@ -90,8 +90,8 @@ public void onStart(ConnectedNode connectedNode) {
float_m.setData(param.getDouble(resolver.resolve("float")));
log.info("float: " + float_m.getData());

final test_ros.Composite composite_m =
topicMessageFactory.newFromType(test_ros.Composite._TYPE);
final rosjava_test_msgs.Composite composite_m =
topicMessageFactory.newFromType(rosjava_test_msgs.Composite._TYPE);
Map composite_map = param.getMap(resolver.resolve("composite"));
composite_m.getA().setW((Double) ((Map) composite_map.get("a")).get("w"));
composite_m.getA().setX((Double) ((Map) composite_map.get("a")).get("x"));
Expand All @@ -101,7 +101,7 @@ public void onStart(ConnectedNode connectedNode) {
composite_m.getB().setY((Double) ((Map) composite_map.get("b")).get("y"));
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
@SuppressWarnings("unchecked")
List<Integer> list = (List<Integer>) param.getList(resolver.resolve("list"));
Expand Down
24 changes: 12 additions & 12 deletions rosjava_test/src/main/java/org/ros/PassthroughTestNode.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,31 +67,31 @@ public void onNewMessage(std_msgs.Int64 m) {
int64Subscriber.addMessageListener(int64_cb);

// TestHeader pass through
final Publisher<test_ros.TestHeader> pub_header =
connectedNode.newPublisher("test_header_out", test_ros.TestHeader._TYPE);
MessageListener<test_ros.TestHeader> header_cb = new MessageListener<test_ros.TestHeader>() {
final Publisher<rosjava_test_msgs.TestHeader> pub_header =
connectedNode.newPublisher("test_header_out", rosjava_test_msgs.TestHeader._TYPE);
MessageListener<rosjava_test_msgs.TestHeader> header_cb = new MessageListener<rosjava_test_msgs.TestHeader>() {
@Override
public void onNewMessage(test_ros.TestHeader m) {
public void onNewMessage(rosjava_test_msgs.TestHeader m) {
m.setOrigCallerId(m.getCallerId());
m.setCallerId(connectedNode.getName().toString());
pub_header.publish(m);
}
};
Subscriber<test_ros.TestHeader> testHeaderSubscriber =
connectedNode.newSubscriber("test_header_in", "test_ros/TestHeader");
Subscriber<rosjava_test_msgs.TestHeader> testHeaderSubscriber =
connectedNode.newSubscriber("test_header_in", "rosjava_test_msgs/TestHeader");
testHeaderSubscriber.addMessageListener(header_cb);

// TestComposite pass through
final Publisher<test_ros.Composite> pub_composite =
connectedNode.newPublisher("composite_out", "test_ros/Composite");
MessageListener<test_ros.Composite> composite_cb = new MessageListener<test_ros.Composite>() {
final Publisher<rosjava_test_msgs.Composite> pub_composite =
connectedNode.newPublisher("composite_out", "rosjava_test_msgs/Composite");
MessageListener<rosjava_test_msgs.Composite> composite_cb = new MessageListener<rosjava_test_msgs.Composite>() {
@Override
public void onNewMessage(test_ros.Composite m) {
public void onNewMessage(rosjava_test_msgs.Composite m) {
pub_composite.publish(m);
}
};
Subscriber<test_ros.Composite> compositeSubscriber =
connectedNode.newSubscriber("composite_in", "test_ros/Composite");
Subscriber<rosjava_test_msgs.Composite> compositeSubscriber =
connectedNode.newSubscriber("composite_in", "rosjava_test_msgs/Composite");
compositeSubscriber.addMessageListener(composite_cb);
}
}
Loading

0 comments on commit 560b9b0

Please sign in to comment.