Skip to content
Snippets Groups Projects
Commit 8f5e84f4 authored by Damon Kohler's avatar Damon Kohler
Browse files

Fix missing spaces in toString methods.

Move ServiceException outside the internal package and simplify error handling for services.
Update the service tutorial and associated documentation.
parent 376661fe
No related branches found
No related tags found
No related merge requests found
Showing
with 98 additions and 51 deletions
......@@ -68,7 +68,7 @@ Creating nodes
--------------
Typically ROS nodes are synonymous with processes. In rosjava, however, nodes
are more like :roswiki:`nodelets` in that many nodes can run in a single
are more like :roswiki:`nodelet`\s in that many nodes can run in a single
process, the Java VM.
Users, like yourself, do not create :javadoc:`org.ros.node.Node`\s. Instead,
......@@ -131,11 +131,11 @@ to handle clean up since it will not delay shutdown.
Publishers and subscribers
--------------------------
The following code is available from the rosjava_tutorial_pubsub package. In
this example, we create a publisher for the chatter topic. That should feel
relatively familiar if you're a ROS veteran. The
:javadoc:`org.ros.topic.Publisher` publishes ``std_msgs.String`` messages to
the ``/chatter`` topic.
The following class (:javadoc:`org.ros.rosjava_tutorial_pubsub.Talker`) is
available from the rosjava_tutorial_pubsub package. In this example, we create
a publisher for the chatter topic. This should feel relatively familiar if
you're a ROS veteran. The :javadoc:`org.ros.topic.Publisher` publishes
``std_msgs.String`` messages to the ``/chatter`` topic.
.. literalinclude:: ../../../../rosjava_tutorial_pubsub/src/main/java/org/ros/rosjava_tutorial_pubsub/Talker.java
:language: java
......@@ -162,7 +162,7 @@ class.
:language: java
:linenos:
In line 43 we see another example of rosjava's asynchornous API. We can add as
In line 42 we see another example of rosjava's asynchornous API. We can add as
many :javadoc:`org.ros.message.MessageListener`\s to our
:javadoc:`org.ros.node.topic.Subscriber` as we like. When a new message is
received, all of our :javadoc:`org.ros.message.MessageListener`\s will be
......@@ -206,6 +206,61 @@ the following commands will remap the default topic /chatter to /foo.
See :roswiki:`Remapping%20Arguments` for more information on passing arguments
to ROS executables.
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
a ROS veteran.
.. literalinclude:: ../../../../rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Server.java
:language: java
:linenos:
The :javadoc:`org.ros.node.service.ServiceResponseBuilder` is called
asynchronously for each incoming request. On line 44 we modify the response
output parameter to contain the sum of the two integers in the request. The
response will be sent once the
:javadoc:`org.ros.node.service.ServiceResponseBuilder#build(T, S)` returns.
Now lets take a look at the :javadoc:`org.ros.rosjava_tutorial_services.Client`
class.
.. literalinclude:: ../../../../rosjava_tutorial_services/src/main/java/org/ros/rosjava_tutorial_services/Client.java
:language: java
:linenos:
In line 51 we see another example of rosjava's asynchornous API. When the response is
received, our :javadoc:`org.ros.node.service.ServiceResponseListener` will be
called with the incoming response as an argument to
:javadoc:`org.ros.node.service.ServiceResponseListener#onSuccess(T)`.
In the event that the server thows a
:javadoc:`org.ros.exception.ServiceException` while building the response,
:javadoc:`org.ros.node.service.ServiceResponseListener#onFailure(RemoteException)`
will be called. The :javadoc:`org.ros.exception.RemoteException` will contain
the error message from the server.
Building and executing these nodes works in the same manner as described above:
.. code-block:: bash
roscd rosjava_tutorial_services
../gradlew installApp
roscore &
./build/rosjava_tutorial_services/bin/rosjava_tutorial_services org.ros.rosjava_tutorial_services.Server &
./build/rosjava_tutorial_services/bin/rosjava_tutorial_services org.ros.rosjava_tutorial_services.Client
At this point, you should see the log message "2 + 2 = 4" appear in your
terminal.
Just as before, you can configure the executed nodes from the command line in
the same way you would any other ROS executable. See
:roswiki:`Remapping%20Arguments` for more information on passing arguments to
ROS executables.
Messages
--------
......@@ -228,11 +283,6 @@ If you want to use messages that you define:
- ensure that my_msgs is in your ROS_PACKAGE_PATH (see :roswiki:`EnvironmentVariables`)
- reinstall rosjava_messages (see :doc:`building`)
Services
--------
TODO
Parameters
----------
......
......@@ -35,5 +35,4 @@ public class ParameterClassCastException extends RosRuntimeException {
public ParameterClassCastException(Throwable throwable) {
super(throwable);
}
}
......@@ -34,5 +34,4 @@ public class ParameterNotFoundException extends RosRuntimeException {
public ParameterNotFoundException(Throwable throwable) {
super(throwable);
}
}
......@@ -36,5 +36,4 @@ public class RemoteException extends RosRuntimeException {
public StatusCode getStatusCode() {
return statusCode;
}
}
......@@ -14,26 +14,22 @@
* the License.
*/
package org.ros.internal.node.service;
import java.nio.ByteBuffer;
import java.nio.charset.Charset;
import org.jboss.netty.buffer.ChannelBuffer;
import org.jboss.netty.buffer.ChannelBuffers;
package org.ros.exception;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class ServiceException extends Exception {
public ServiceException(String message) {
super(message);
public ServiceException(final Throwable throwable) {
super(throwable);
}
public ChannelBuffer getMessageAsChannelBuffer() {
ByteBuffer encodedMessage = Charset.forName("US-ASCII").encode(getMessage());
return ChannelBuffers.wrappedBuffer(encodedMessage);
public ServiceException(final String message, final Throwable throwable) {
super(message, throwable);
}
public ServiceException(final String message) {
super(message);
}
}
......@@ -32,5 +32,4 @@ public class ServiceNotFoundException extends RosException {
public ServiceNotFoundException(final String message) {
super(message);
}
}
......@@ -18,6 +18,8 @@ package org.ros.internal.node;
import com.google.common.annotations.VisibleForTesting;
import org.ros.node.service.ServiceResponseBuilder;
import org.apache.commons.logging.Log;
import org.ros.concurrent.CancellableLoop;
import org.ros.concurrent.ListenerCollection;
......@@ -37,7 +39,6 @@ import org.ros.internal.node.service.ServiceDeclaration;
import org.ros.internal.node.service.ServiceFactory;
import org.ros.internal.node.service.ServiceIdentifier;
import org.ros.internal.node.service.ServiceManager;
import org.ros.internal.node.service.ServiceResponseBuilder;
import org.ros.internal.node.topic.PublisherFactory;
import org.ros.internal.node.topic.SubscriberFactory;
import org.ros.internal.node.topic.TopicDeclaration;
......
......@@ -18,6 +18,8 @@ package org.ros.internal.node.service;
import com.google.common.base.Preconditions;
import org.ros.node.service.ServiceResponseBuilder;
import org.apache.commons.logging.Log;
import org.apache.commons.logging.LogFactory;
import org.jboss.netty.buffer.ChannelBuffer;
......
......@@ -18,6 +18,8 @@ package org.ros.internal.node.service;
import com.google.common.base.Preconditions;
import org.ros.node.service.ServiceResponseBuilder;
import org.ros.internal.message.service.ServiceDescription;
import org.ros.internal.node.server.SlaveServer;
import org.ros.internal.node.server.master.MasterServer;
......
......@@ -16,11 +16,11 @@
package org.ros.internal.node.service;
import java.net.URI;
import com.google.common.base.Preconditions;
import org.ros.namespace.GraphName;
import com.google.common.base.Preconditions;
import java.net.URI;
/**
* @author damonkohler@google.com (Damon Kohler)
......
......@@ -21,11 +21,14 @@ import org.jboss.netty.buffer.ChannelBuffers;
import org.jboss.netty.channel.ChannelHandlerContext;
import org.jboss.netty.channel.MessageEvent;
import org.jboss.netty.channel.SimpleChannelHandler;
import org.ros.exception.ServiceException;
import org.ros.message.MessageDeserializer;
import org.ros.message.MessageFactory;
import org.ros.message.MessageSerializer;
import org.ros.node.service.ServiceResponseBuilder;
import java.nio.ByteBuffer;
import java.nio.charset.Charset;
import java.util.concurrent.ExecutorService;
/**
......@@ -68,10 +71,11 @@ class ServiceRequestHandler<T, S> extends SimpleChannelHandler {
}
private void handleError(final ChannelHandlerContext ctx, ServiceServerResponse response,
ServiceException ex) {
String message) {
response.setErrorCode(0);
response.setMessageLength(ex.getMessage().length());
response.setMessage(ex.getMessageAsChannelBuffer());
ByteBuffer encodedMessage = Charset.forName("US-ASCII").encode(message);
response.setMessageLength(encodedMessage.limit());
response.setMessage(ChannelBuffers.wrappedBuffer(encodedMessage));
ctx.getChannel().write(response);
}
......@@ -90,7 +94,7 @@ class ServiceRequestHandler<T, S> extends SimpleChannelHandler {
responseBuffer =
ChannelBuffers.wrappedBuffer(handleRequest(requestBuffer.toByteBuffer()));
} catch (ServiceException ex) {
handleError(ctx, response, ex);
handleError(ctx, response, ex.getMessage());
return;
}
handleSuccess(ctx, response, responseBuffer);
......
......@@ -16,10 +16,11 @@
package org.ros.node;
import org.ros.node.service.ServiceResponseBuilder;
import org.apache.commons.logging.Log;
import org.ros.concurrent.CancellableLoop;
import org.ros.exception.ServiceNotFoundException;
import org.ros.internal.node.service.ServiceResponseBuilder;
import org.ros.internal.node.xmlrpc.MasterXmlRpcEndpoint;
import org.ros.message.MessageFactory;
import org.ros.message.MessageSerializationFactory;
......
......@@ -14,9 +14,9 @@
* the License.
*/
package org.ros.internal.node.service;
package org.ros.node.service;
import org.ros.node.service.ServiceServer;
import org.ros.exception.ServiceException;
/**
* Builds a service response given a service request.
......
......@@ -24,9 +24,8 @@ import org.junit.Test;
import org.ros.RosTest;
import org.ros.exception.RemoteException;
import org.ros.exception.RosRuntimeException;
import org.ros.exception.ServiceException;
import org.ros.exception.ServiceNotFoundException;
import org.ros.internal.node.service.ServiceException;
import org.ros.internal.node.service.ServiceResponseBuilder;
import org.ros.namespace.GraphName;
import org.ros.node.Node;
import org.ros.node.NodeMain;
......
......@@ -32,5 +32,4 @@ public class RosException extends Exception {
public RosException(final String message) {
super(message);
}
}
......@@ -24,7 +24,6 @@ import org.ros.node.Node;
import org.ros.node.NodeMain;
import org.ros.node.service.ServiceClient;
import org.ros.node.service.ServiceResponseListener;
import test_ros.AddTwoInts.Response;
/**
* A simple {@link ServiceClient} {@link NodeMain}.
......@@ -51,7 +50,7 @@ public class Client implements NodeMain {
request.setB(2);
serviceClient.call(request, new ServiceResponseListener<test_ros.AddTwoInts.Response>() {
@Override
public void onSuccess(Response response) {
public void onSuccess(test_ros.AddTwoInts.Response response) {
node.getLog().info(
String.format("%d + %d = %d", request.getA(), request.getB(), response.getSum()));
}
......
......@@ -16,14 +16,11 @@
package org.ros.rosjava_tutorial_services;
import org.ros.internal.node.service.ServiceException;
import org.ros.internal.node.service.ServiceResponseBuilder;
import org.ros.namespace.GraphName;
import org.ros.node.Node;
import org.ros.node.NodeMain;
import org.ros.node.service.ServiceResponseBuilder;
import org.ros.node.service.ServiceServer;
import test_ros.AddTwoInts.Request;
import test_ros.AddTwoInts.Response;
/**
* This is a simple {@link ServiceServer} {@link NodeMain}.
......@@ -42,7 +39,8 @@ public class Server implements NodeMain {
node.newServiceServer("add_two_ints", test_ros.AddTwoInts._TYPE,
new ServiceResponseBuilder<test_ros.AddTwoInts.Request, test_ros.AddTwoInts.Response>() {
@Override
public void build(Request request, Response response) throws ServiceException {
public void build(test_ros.AddTwoInts.Request request,
test_ros.AddTwoInts.Response response) {
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