Skip to content
This repository was archived by the owner on Aug 11, 2023. It is now read-only.

Commit 111c1d1

Browse files
author
Juan Ignacio Ubeira
authored
Merge pull request #295 from StefanGlaser/kinetic
Adding TCP-NO-DELAY transport hint
2 parents a88a64a + 391a0a9 commit 111c1d1

File tree

6 files changed

+85
-8
lines changed

6 files changed

+85
-8
lines changed

rosjava/src/main/java/org/ros/internal/node/DefaultNode.java

+14-3
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@
6565
import org.ros.node.topic.DefaultSubscriberListener;
6666
import org.ros.node.topic.Publisher;
6767
import org.ros.node.topic.Subscriber;
68+
import org.ros.node.topic.TransportHints;
6869
import org.ros.time.ClockTopicTimeProvider;
6970
import org.ros.time.TimeProvider;
7071

@@ -283,7 +284,7 @@ public <T> Publisher<T> newPublisher(GraphName topicName, String messageType) {
283284
TopicDescription topicDescription =
284285
nodeConfiguration.getTopicDescriptionFactory().newFromType(messageType);
285286
TopicDeclaration topicDeclaration =
286-
TopicDeclaration.newFromTopicName(resolvedTopicName, topicDescription);
287+
TopicDeclaration.newFromTopicName(resolvedTopicName, topicDescription, null);
287288
org.ros.message.MessageSerializer<T> serializer = newMessageSerializer(messageType);
288289
return publisherFactory.newOrExisting(topicDeclaration, serializer);
289290
}
@@ -295,19 +296,29 @@ public <T> Publisher<T> newPublisher(String topicName, String messageType) {
295296

296297
@Override
297298
public <T> Subscriber<T> newSubscriber(GraphName topicName, String messageType) {
299+
return newSubscriber(topicName, messageType, null);
300+
}
301+
302+
@Override
303+
public <T> Subscriber<T> newSubscriber(GraphName topicName, String messageType, TransportHints transportHints) {
298304
GraphName resolvedTopicName = resolveName(topicName);
299305
TopicDescription topicDescription =
300306
nodeConfiguration.getTopicDescriptionFactory().newFromType(messageType);
301307
TopicDeclaration topicDeclaration =
302-
TopicDeclaration.newFromTopicName(resolvedTopicName, topicDescription);
308+
TopicDeclaration.newFromTopicName(resolvedTopicName, topicDescription, transportHints);
303309
MessageDeserializer<T> deserializer = newMessageDeserializer(messageType);
304310
Subscriber<T> subscriber = subscriberFactory.newOrExisting(topicDeclaration, deserializer);
305311
return subscriber;
306312
}
307313

308314
@Override
309315
public <T> Subscriber<T> newSubscriber(String topicName, String messageType) {
310-
return newSubscriber(GraphName.of(topicName), messageType);
316+
return newSubscriber(GraphName.of(topicName), messageType, null);
317+
}
318+
319+
@Override
320+
public <T> Subscriber<T> newSubscriber(String topicName, String messageType, TransportHints transportHints) {
321+
return newSubscriber(GraphName.of(topicName), messageType, transportHints);
311322
}
312323

313324
@Override

rosjava/src/main/java/org/ros/internal/node/response/TopicListResultFactory.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ public List<TopicDeclaration> newFromValue(Object value) {
4343
String name = (String) ((Object[]) topic)[0];
4444
String type = (String) ((Object[]) topic)[1];
4545
descriptions.add(TopicDeclaration.newFromTopicName(GraphName.of(name), new TopicDescription(type, null,
46-
null)));
46+
null), null));
4747
}
4848
return descriptions;
4949
}

rosjava/src/main/java/org/ros/internal/node/topic/TopicDeclaration.java

+14-4
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
import org.ros.internal.transport.ConnectionHeader;
2424
import org.ros.internal.transport.ConnectionHeaderFields;
2525
import org.ros.namespace.GraphName;
26+
import org.ros.node.topic.TransportHints;
2627

2728
import java.util.List;
2829
import java.util.Map;
@@ -36,6 +37,7 @@ public class TopicDeclaration {
3637

3738
private final TopicIdentifier topicIdentifier;
3839
private final TopicDescription topicDescription;
40+
private final TransportHints transportHints;
3941

4042
/**
4143
* @param header
@@ -49,19 +51,26 @@ public static TopicDeclaration newFromHeader(Map<String, String> header) {
4951
String definition = header.get(ConnectionHeaderFields.MESSAGE_DEFINITION);
5052
String md5Checksum = header.get(ConnectionHeaderFields.MD5_CHECKSUM);
5153
TopicDescription topicDescription = new TopicDescription(type, definition, md5Checksum);
52-
return new TopicDeclaration(new TopicIdentifier(name), topicDescription);
54+
boolean tcpNoDelay = "1".equals(header.get(ConnectionHeaderFields.TCP_NODELAY));
55+
return new TopicDeclaration(new TopicIdentifier(name), topicDescription, new TransportHints(tcpNoDelay));
5356
}
5457

5558
public static TopicDeclaration newFromTopicName(GraphName topicName,
56-
TopicDescription topicDescription) {
57-
return new TopicDeclaration(new TopicIdentifier(topicName), topicDescription);
59+
TopicDescription topicDescription, TransportHints transportHints) {
60+
return new TopicDeclaration(new TopicIdentifier(topicName), topicDescription, transportHints);
5861
}
5962

60-
public TopicDeclaration(TopicIdentifier topicIdentifier, TopicDescription topicDescription) {
63+
public TopicDeclaration(TopicIdentifier topicIdentifier, TopicDescription topicDescription, TransportHints transportHints) {
6164
Preconditions.checkNotNull(topicIdentifier);
6265
Preconditions.checkNotNull(topicDescription);
6366
this.topicIdentifier = topicIdentifier;
6467
this.topicDescription = topicDescription;
68+
69+
if (transportHints != null) {
70+
this.transportHints = transportHints;
71+
} else {
72+
this.transportHints = new TransportHints();
73+
}
6574
}
6675

6776
public TopicIdentifier getIdentifier() {
@@ -84,6 +93,7 @@ public ConnectionHeader toConnectionHeader() {
8493
topicDescription.getDefinition());
8594
connectionHeader.addField(ConnectionHeaderFields.MD5_CHECKSUM,
8695
topicDescription.getMd5Checksum());
96+
connectionHeader.addField(ConnectionHeaderFields.TCP_NODELAY, transportHints.getTcpNoDelay() ? "1" : "0");
8797
return connectionHeader;
8898
}
8999

rosjava/src/main/java/org/ros/internal/transport/tcp/TcpServerHandshakeHandler.java

+4
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,10 @@ private void handleSubscriberHandshake(ChannelHandlerContext ctx, MessageEvent e
9696
DefaultPublisher<?> publisher = topicParticipantManager.getPublisher(topicName);
9797
ChannelBuffer outgoingBuffer = publisher.finishHandshake(incomingConnectionHeader);
9898
Channel channel = ctx.getChannel();
99+
if (incomingConnectionHeader.hasField(ConnectionHeaderFields.TCP_NODELAY)) {
100+
boolean tcpNoDelay = "1".equals(incomingConnectionHeader.getField(ConnectionHeaderFields.TCP_NODELAY));
101+
channel.getConfig().setOption("tcpNoDelay", tcpNoDelay);
102+
}
99103
ChannelFuture future = channel.write(outgoingBuffer).await();
100104
if (!future.isSuccess()) {
101105
throw new RosRuntimeException(future.getCause());

rosjava/src/main/java/org/ros/node/ConnectedNode.java

+19
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
import org.ros.node.service.ServiceServer;
2727
import org.ros.node.topic.Publisher;
2828
import org.ros.node.topic.Subscriber;
29+
import org.ros.node.topic.TransportHints;
2930

3031
import java.net.URI;
3132

@@ -82,11 +83,29 @@ public interface ConnectedNode extends Node {
8283
*/
8384
<T> Subscriber<T> newSubscriber(GraphName topicName, String messageType);
8485

86+
/**
87+
* @param <T>
88+
* the message type to create the {@link Subscriber} for
89+
* @param topicName
90+
* the topic name to be subscribed to, this will be auto resolved
91+
* @param messageType
92+
* the message data type (e.g. "std_msgs/String")
93+
* @param transportHints
94+
* the transport hints
95+
* @return a {@link Subscriber} for the specified topic
96+
*/
97+
<T> Subscriber<T> newSubscriber(GraphName topicName, String messageType, TransportHints transportHints);
98+
8599
/**
86100
* @see #newSubscriber(GraphName, String)
87101
*/
88102
<T> Subscriber<T> newSubscriber(String topicName, String messageType);
89103

104+
/**
105+
* @see #newSubscriber(GraphName, String, TransportHints)
106+
*/
107+
<T> Subscriber<T> newSubscriber(String topicName, String messageType, TransportHints transportHints);
108+
90109
/**
91110
* Create a new {@link ServiceServer}.
92111
*
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
package org.ros.node.topic;
2+
3+
import org.ros.node.ConnectedNode;
4+
5+
6+
/**
7+
* Provides a way of specifying network transport hints to
8+
* {@link ConnectedNode#newSubscriber(org.ros.namespace.GraphName, String, TransportHints)} and
9+
* {@link ConnectedNode#newSubscriber(String, String, TransportHints)}.
10+
*
11+
* @author [email protected] (Stefan Glaser)
12+
*/
13+
public class TransportHints {
14+
15+
private boolean tcpNoDelay;
16+
17+
public TransportHints() {
18+
this(false);
19+
}
20+
21+
public TransportHints(boolean tcpNoDelay) {
22+
this.tcpNoDelay = tcpNoDelay;
23+
}
24+
25+
public TransportHints tcpNoDelay(boolean tcpNoDelay) {
26+
this.tcpNoDelay = tcpNoDelay;
27+
return this;
28+
}
29+
30+
public boolean getTcpNoDelay() {
31+
return tcpNoDelay;
32+
}
33+
}

0 commit comments

Comments
 (0)