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;
00018
00019 import org.ros.message.MessageListener;
00020 import org.ros.namespace.GraphName;
00021 import org.ros.node.AbstractNodeMain;
00022 import org.ros.node.ConnectedNode;
00023 import org.ros.node.topic.Publisher;
00024 import org.ros.node.topic.Subscriber;
00025
00032 public class PassthroughTestNode extends AbstractNodeMain {
00033
00034 @Override
00035 public GraphName getDefaultNodeName() {
00036 return GraphName.of("rosjava/passthrough_test_node");
00037 }
00038
00039 @Override
00040 public void onStart(final ConnectedNode connectedNode) {
00041
00042
00043
00044
00045
00046 final Publisher<std_msgs.String> pub_string =
00047 connectedNode.newPublisher("string_out", std_msgs.String._TYPE);
00048 MessageListener<std_msgs.String> string_cb = new MessageListener<std_msgs.String>() {
00049 @Override
00050 public void onNewMessage(std_msgs.String m) {
00051 pub_string.publish(m);
00052 }
00053 };
00054 Subscriber<std_msgs.String> stringSubscriber =
00055 connectedNode.newSubscriber("string_in", "std_msgs/String");
00056 stringSubscriber.addMessageListener(string_cb);
00057
00058
00059 final Publisher<std_msgs.Int64> pub_int64 = connectedNode.newPublisher("int64_out", "std_msgs/Int64");
00060 MessageListener<std_msgs.Int64> int64_cb = new MessageListener<std_msgs.Int64>() {
00061 @Override
00062 public void onNewMessage(std_msgs.Int64 m) {
00063 pub_int64.publish(m);
00064 }
00065 };
00066 Subscriber<std_msgs.Int64> int64Subscriber = connectedNode.newSubscriber("int64_in", "std_msgs/Int64");
00067 int64Subscriber.addMessageListener(int64_cb);
00068
00069
00070 final Publisher<rosjava_test_msgs.TestHeader> pub_header =
00071 connectedNode.newPublisher("test_header_out", rosjava_test_msgs.TestHeader._TYPE);
00072 MessageListener<rosjava_test_msgs.TestHeader> header_cb = new MessageListener<rosjava_test_msgs.TestHeader>() {
00073 @Override
00074 public void onNewMessage(rosjava_test_msgs.TestHeader m) {
00075 m.setOrigCallerId(m.getCallerId());
00076 m.setCallerId(connectedNode.getName().toString());
00077 pub_header.publish(m);
00078 }
00079 };
00080 Subscriber<rosjava_test_msgs.TestHeader> testHeaderSubscriber =
00081 connectedNode.newSubscriber("test_header_in", "rosjava_test_msgs/TestHeader");
00082 testHeaderSubscriber.addMessageListener(header_cb);
00083
00084
00085 final Publisher<rosjava_test_msgs.Composite> pub_composite =
00086 connectedNode.newPublisher("composite_out", "rosjava_test_msgs/Composite");
00087 MessageListener<rosjava_test_msgs.Composite> composite_cb = new MessageListener<rosjava_test_msgs.Composite>() {
00088 @Override
00089 public void onNewMessage(rosjava_test_msgs.Composite m) {
00090 pub_composite.publish(m);
00091 }
00092 };
00093 Subscriber<rosjava_test_msgs.Composite> compositeSubscriber =
00094 connectedNode.newSubscriber("composite_in", "rosjava_test_msgs/Composite");
00095 compositeSubscriber.addMessageListener(composite_cb);
00096 }
00097 }