@WebSocket public class RosBridge extends Object
subscribe(SubscriptionRequestMsg, RosListenDelegate).
The input SubscriptionRequestMsg allows you to iteratively build all the optional fields
you can set to detail the subscription, such as whether the messages should be fragmented in size,
the queue length, throttle rate, etc. If data is pushed quickly, it is recommended that you
set the throttle rate and queue length to 1 or you may observe increasing latency in the messages.
Png compression is currently not supported. If the message type
is not set, and the topic either does not exist or you have never subscribed to that topic previously,
Rosbridge may fail to subscribe. There are also additional methods for subscribing that take the parameters
of a subscription as arguments to the method.
Publishing is also supported with the publish(String, String, Object) method, but you should
consider using the Publisher class wrapper for streamlining publishing.
To create and connect to rosbridge, you can either instantiate with the default constructor
and then call connect(String) or use the static method createConnection(String) which
creates a RosBridge instance and then connects.
An example URI to provide as a parameter is: ws://localhost:9090, where 9090 is the default Rosbridge server port.
If you need to handle messages with larger sizes, you should subclass RosBridge and annotate the class
with WebSocket with the parameter maxTextMessageSize set to the desired buffer size. For example:
@WebSocket(maxTextMessageSize = 500 * 1024)
public class BigRosBridge extends RosBridge{
}
Note that the subclass does not need to override any methods; subclassing is performed purely to set the buffer size in the annotation value. Then you can instantiate BigRosBridge and call its inherited connect method.
| Modifier and Type | Class and Description |
|---|---|
static class |
RosBridge.FragmentManager |
static class |
RosBridge.RosBridgeSubscriber
Class for managing all the listeners that have subscribed to a topic on Rosbridge.
|
| Modifier and Type | Field and Description |
|---|---|
protected CountDownLatch |
closeLatch |
protected Map<String,RosBridge.FragmentManager> |
fragementManagers |
protected boolean |
hasConnected |
protected Map<String,RosBridge.RosBridgeSubscriber> |
listeners |
protected boolean |
printMessagesAsReceived |
protected Set<String> |
publishedTopics |
protected org.eclipse.jetty.websocket.api.Session |
session |
| Constructor and Description |
|---|
RosBridge() |
| Modifier and Type | Method and Description |
|---|---|
void |
advertise(String topic,
String type)
Advertises that this object will be publishing to a ROS topic.
|
boolean |
awaitClose(int duration,
TimeUnit unit)
Use this to close the connection
|
void |
connect(String rosBridgeURI)
Connects to the Rosbridge host at the provided URI.
|
void |
connect(String rosBridgeURI,
boolean waitForConnection)
Connects to the Rosbridge host at the provided URI.
|
static RosBridge |
createConnection(String rosBridgeURI)
Creates a default RosBridge and connects it to the ROS Bridge websocket server located at rosBridgeURI.
|
void |
formatAndSend(Object o)
Attempts to turn the the provided object into a JSON message and send it to the ROSBridge server.
|
boolean |
hasConnected()
Indicates whether the connection has been made
|
void |
onClose(int statusCode,
String reason) |
void |
onConnect(org.eclipse.jetty.websocket.api.Session session) |
void |
onMessage(String msg) |
boolean |
printMessagesAsReceived()
Returns whether ROSBridge will print all ROSBridge messages as they are received to the command line.
|
protected void |
processFragment(com.fasterxml.jackson.databind.JsonNode node) |
void |
publish(String topic,
String type,
Object msg)
Publishes to a topic.
|
void |
publishJsonMsg(String topic,
String type,
String jsonMsg)
Publishes to a topic with a ros message represented in its JSON string form.
|
void |
removeListener(String topic,
RosListenDelegate delegate)
Stops a
RosListenDelegate from receiving messages from Rosbridge. |
void |
sendRawMessage(String message)
Sends the provided fully specified message to the ROS Bridge server.
|
void |
setPrintMessagesAsReceived(boolean printMessagesAsReceived)
Sets whether ROSBridge should print all ROSBridge messages as they are received to the command.
|
void |
subscribe(String topic,
String type,
RosListenDelegate delegate)
Subscribes to a ros topic.
|
void |
subscribe(String topic,
String type,
RosListenDelegate delegate,
int throttleRate,
int queueLength)
Subscribes to a ros topic.
|
void |
subscribe(SubscriptionRequestMsg request,
RosListenDelegate delegate)
Subscribes to a topic with the subscription parameters specified in the provided
SubscriptionRequestMsg. |
void |
unsubscribe(String topic)
Unsubscribes from a topic.
|
void |
waitForConnection()
Blocks execution until a connection to the ros bridge server is established.
|
protected final CountDownLatch closeLatch
protected org.eclipse.jetty.websocket.api.Session session
protected Map<String,RosBridge.RosBridgeSubscriber> listeners
protected Map<String,RosBridge.FragmentManager> fragementManagers
protected boolean hasConnected
protected boolean printMessagesAsReceived
public static RosBridge createConnection(String rosBridgeURI)
waitForConnection() method
before publishing or subscribing.rosBridgeURI - the URI to the ROS Bridge websocket server. Note that ROS Bridge by default uses port 9090. An example URI is: ws://localhost:9090public void connect(String rosBridgeURI)
rosBridgeURI - the URI to the ROS Bridge websocket server. Note that ROS Bridge by default uses port 9090. An example URI is: ws://localhost:9090public void connect(String rosBridgeURI, boolean waitForConnection)
rosBridgeURI - the URI to the ROS Bridge websocket server. Note that ROS Bridge by default uses port 9090. An example URI is: ws://localhost:9090waitForConnection - if true, then this method will block until the connection is established. If false, then return immediately.public void waitForConnection()
public boolean hasConnected()
public boolean printMessagesAsReceived()
public void setPrintMessagesAsReceived(boolean printMessagesAsReceived)
printMessagesAsReceived - if true, then ROSBridge will print all ROSBridge messages as they are received to the command line. Otherwise is silent.public boolean awaitClose(int duration,
TimeUnit unit)
throws InterruptedException
duration - the time in some units until closing.unit - the unit of time in which duration is measured.CountDownLatch.await() method.InterruptedException@OnWebSocketClose
public void onClose(int statusCode,
String reason)
@OnWebSocketConnect public void onConnect(org.eclipse.jetty.websocket.api.Session session)
@OnWebSocketMessage public void onMessage(String msg)
public void subscribe(String topic, String type, RosListenDelegate delegate)
topic - the to subscribe totype - the message type of the topic. Pass null for type inference.delegate - the delegate that receives updates to the topicpublic void subscribe(String topic, String type, RosListenDelegate delegate, int throttleRate, int queueLength)
topic - the to subscribe totype - the message type of the topic. Pass null for type inference.delegate - the delegate that receives updates to the topicthrottleRate - the minimum amount of time (in ms) that must elapse between messages being sent from the serverqueueLength - the size of the queue to buffer messages. Messages are buffered as a result of the throttle_rate.public void subscribe(SubscriptionRequestMsg request, RosListenDelegate delegate)
SubscriptionRequestMsg.
The RosListenDelegate will be notified every time there is a publish to the specified topic.request - the subscription request details.delegate - the delegate that will receive messages each time a message is published to the topic.public void removeListener(String topic, RosListenDelegate delegate)
RosListenDelegate from receiving messages from Rosbridge.topic - the topic on which the listener subscribed.delegate - the delegate to remove.public void advertise(String topic, String type)
topic - the topic to which this object will be publishing.type - the ROS message type of the topic.public void unsubscribe(String topic)
RosListenDelegate
objects subscribed to a topic, they will all unsubscribe. If you want to remove only
one, instead use removeListener(String, RosListenDelegate).topic - the topic from which to unsubscribe.public void publish(String topic, String type, Object msg)
topic - the topic to publish totype - the message type of the topicmsg - should be a Map or a Java Bean, specifying the ROS messagepublic void publishJsonMsg(String topic, String type, String jsonMsg)
topic - the topic to publish totype - the message type of the topicjsonMsg - the JSON string of the ROS message.public void sendRawMessage(String message)
message - the message to send to Rosbridge.public void formatAndSend(Object o)
o - the object to turn into a JSON message and send.protected void processFragment(com.fasterxml.jackson.databind.JsonNode node)
Copyright © 2016. All rights reserved.