Skip to content
Snippets Groups Projects
Commit 073bc19c authored by Sebastian Ebert's avatar Sebastian Ebert
Browse files

removed bazel build, fixed dependencies, removed non-core-packages

parent 111c1d10
Branches
No related tags found
No related merge requests found
Showing
with 0 additions and 1388 deletions
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_geometry;
import static org.junit.Assert.assertEquals;
import static org.junit.Assert.assertTrue;
import org.junit.Before;
import org.junit.Test;
import org.ros.internal.message.DefaultMessageFactory;
import org.ros.internal.message.definition.MessageDefinitionReflectionProvider;
import org.ros.message.MessageDefinitionProvider;
import org.ros.message.MessageFactory;
import org.ros.message.Time;
import org.ros.namespace.GraphName;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class FrameTransformTreeTest {
private FrameTransformTree frameTransformTree;
private MessageDefinitionProvider messageDefinitionProvider;
private MessageFactory messageFactory;
@Before
public void before() {
frameTransformTree = new FrameTransformTree();
messageDefinitionProvider = new MessageDefinitionReflectionProvider();
messageFactory = new DefaultMessageFactory(messageDefinitionProvider);
}
@Test
public void testUpdateAndGet() {
FrameTransform frameTransform = new FrameTransform(Transform.identity(),
GraphName.of("foo"), GraphName.of("bar"), new Time());
frameTransformTree.update(frameTransform);
assertEquals(frameTransform, frameTransformTree.get("foo"));
}
@Test
public void testUpdateAndGetWithTransformStampedMessage() {
FrameTransform frameTransform = new FrameTransform(Transform.identity(),
GraphName.of("foo"), GraphName.of("bar"), new Time());
frameTransformTree.update(newTransformStampedMessage(Transform.identity(),
"foo", "bar", new Time()));
assertEquals(frameTransform, frameTransformTree.get("foo"));
}
private geometry_msgs.TransformStamped newTransformStampedMessage(
Transform transform, String source, String target, Time time) {
geometry_msgs.TransformStamped message = messageFactory
.newFromType(geometry_msgs.TransformStamped._TYPE);
FrameTransform frameTransform = new FrameTransform(transform,
GraphName.of(source), GraphName.of(target), time);
frameTransform.toTransformStampedMessage(message);
return message;
}
@Test
public void testIdentityTransforms() {
frameTransformTree.update(newTransformStampedMessage(Transform.identity(),
"baz", "bar", new Time()));
frameTransformTree.update(newTransformStampedMessage(Transform.identity(),
"bar", "foo", new Time()));
// Full tree transform.
{
FrameTransform frameTransform = frameTransformTree
.transform("baz", "foo");
assertTrue(frameTransform != null);
assertEquals(GraphName.of("baz"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("foo"), frameTransform.getTargetFrame());
assertEquals(Transform.identity(), frameTransform.getTransform());
}
// Same node transform.
{
FrameTransform frameTransform = frameTransformTree
.transform("baz", "baz");
assertTrue(frameTransform != null);
assertEquals(GraphName.of("baz"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("baz"), frameTransform.getTargetFrame());
assertEquals(Transform.identity(), frameTransform.getTransform());
}
// Same node transform.
{
FrameTransform frameTransform = frameTransformTree
.transform("bar", "bar");
assertTrue(frameTransform != null);
assertEquals(GraphName.of("bar"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("bar"), frameTransform.getTargetFrame());
assertEquals(Transform.identity(), frameTransform.getTransform());
}
// Root-to-root transform.
{
FrameTransform frameTransform = frameTransformTree
.transform("foo", "foo");
assertTrue(frameTransform != null);
assertEquals(GraphName.of("foo"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("foo"), frameTransform.getTargetFrame());
assertEquals(Transform.identity(), frameTransform.getTransform());
}
// Root-to-leaf transform.
{
FrameTransform frameTransform = frameTransformTree
.transform("foo", "baz");
assertTrue(frameTransform != null);
assertEquals(GraphName.of("foo"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("baz"), frameTransform.getTargetFrame());
assertEquals(Transform.identity(), frameTransform.getTransform());
}
}
/**
* Fills the {@link FrameTransformTree} with the following frame topography:
*
* <pre>
* foo
* bar bop
* baz fuz
* </pre>
*/
private void updateFrameTransformTree() {
{
Transform transform = Transform.translation(0, 1, 0);
frameTransformTree.update(newTransformStampedMessage(transform, "bar",
"foo", new Time()));
}
{
Transform transform = Transform.xRotation(Math.PI / 2);
frameTransformTree.update(newTransformStampedMessage(transform, "baz",
"bar", new Time()));
}
{
Transform transform = Transform.translation(1, 0, 0);
frameTransformTree.update(newTransformStampedMessage(transform, "bop",
"foo", new Time()));
}
{
Transform transform = Transform.yRotation(Math.PI / 2);
frameTransformTree.update(newTransformStampedMessage(transform, "fuz",
"bop", new Time()));
}
}
private void checkBazToFooTransform(FrameTransform frameTransform) {
// If we were to reverse the order of the transforms in our implementation,
// we would expect the translation vector to be <0, 0, 1> instead.
Transform transform = Transform.translation(0, 1, 0).multiply(
Transform.xRotation(Math.PI / 2));
Quaternion rotationAndScale = transform.getRotationAndScale();
assertTrue(String.format("%s is not neutral.", rotationAndScale),
rotationAndScale.isAlmostNeutral(1e-9));
assertEquals(GraphName.of("baz"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("foo"), frameTransform.getTargetFrame());
assertTrue(transform.almostEquals(frameTransform.getTransform(), 1e-9));
}
@Test
public void testTransformBazToRoot() {
updateFrameTransformTree();
checkBazToFooTransform(frameTransformTree.transformToRoot(GraphName
.of("baz")));
}
@Test
public void testTransformBazToFoo() {
updateFrameTransformTree();
checkBazToFooTransform(frameTransformTree.transform("baz", "foo"));
checkBazToFooTransform(frameTransformTree.transform("foo", "baz").invert());
}
private void checkFuzToFooTransform(FrameTransform frameTransform) {
// If we were to reverse the order of the transforms in our implementation,
// we would expect the translation vector to be <0, 0, 1> instead.
Transform transform = Transform.translation(1, 0, 0).multiply(
Transform.yRotation(Math.PI / 2));
Quaternion rotationAndScale = transform.getRotationAndScale();
assertTrue(String.format("%s is not neutral.", rotationAndScale),
rotationAndScale.isAlmostNeutral(1e-9));
assertEquals(GraphName.of("fuz"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("foo"), frameTransform.getTargetFrame());
assertTrue(
String.format("Expected %s != %s", transform,
frameTransform.getTransform()),
transform.almostEquals(frameTransform.getTransform(), 1e-9));
}
@Test
public void testTransformFuzToRoot() {
updateFrameTransformTree();
checkFuzToFooTransform(frameTransformTree.transformToRoot(GraphName
.of("fuz")));
}
@Test
public void testTransformFuzToFoo() {
updateFrameTransformTree();
checkFuzToFooTransform(frameTransformTree.transform("fuz", "foo"));
checkFuzToFooTransform(frameTransformTree.transform("foo", "fuz").invert());
}
@Test
public void testTransformBazToFuz() {
updateFrameTransformTree();
FrameTransform frameTransform = frameTransformTree.transform("baz", "fuz");
Transform transform = Transform.yRotation(Math.PI / 2).invert()
.multiply(Transform.translation(1, 0, 0).invert())
.multiply(Transform.translation(0, 1, 0))
.multiply(Transform.xRotation(Math.PI / 2));
assertTrue(transform.getRotationAndScale().isAlmostNeutral(1e-9));
assertEquals(GraphName.of("baz"), frameTransform.getSourceFrame());
assertEquals(GraphName.of("fuz"), frameTransform.getTargetFrame());
assertTrue(
String.format("Expected %s != %s", transform,
frameTransform.getTransform()),
transform.almostEquals(frameTransform.getTransform(), 1e-9));
}
@Test
public void testTimeTravel() {
FrameTransform frameTransform1 = new FrameTransform(Transform.identity(),
GraphName.of("foo"), GraphName.of("bar"), new Time());
FrameTransform frameTransform2 = new FrameTransform(Transform.identity(),
GraphName.of("foo"), GraphName.of("bar"), new Time(2));
FrameTransform frameTransform3 = new FrameTransform(Transform.identity(),
GraphName.of("foo"), GraphName.of("bar"), new Time(4));
frameTransformTree.update(frameTransform1);
frameTransformTree.update(frameTransform2);
frameTransformTree.update(frameTransform3);
assertEquals(frameTransform3, frameTransformTree.get("foo"));
assertEquals(frameTransform1, frameTransformTree.get("foo", new Time()));
assertEquals(frameTransform1, frameTransformTree.get("foo", new Time(0.5)));
assertEquals(frameTransform2, frameTransformTree.get("foo", new Time(1.5)));
assertEquals(frameTransform2, frameTransformTree.get("foo", new Time(2)));
assertEquals(frameTransform3, frameTransformTree.get("foo", new Time(10)));
}
}
/*
* Copyright (C) 2012 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_geometry;
import static org.junit.Assert.assertEquals;
import org.junit.Test;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class QuaternionTest {
@Test
public void testAxisAngleToQuaternion() {
Quaternion quaternion;
quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), 0);
assertEquals(0, quaternion.getX(), 1e-9);
assertEquals(0, quaternion.getY(), 1e-9);
assertEquals(0, quaternion.getZ(), 1e-9);
assertEquals(1, quaternion.getW(), 1e-9);
quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), Math.PI);
assertEquals(0, quaternion.getX(), 1e-9);
assertEquals(0, quaternion.getY(), 1e-9);
assertEquals(1, quaternion.getZ(), 1e-9);
assertEquals(0, quaternion.getW(), 1e-9);
quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), Math.PI / 2);
assertEquals(0, quaternion.getX(), 1e-9);
assertEquals(0, quaternion.getY(), 1e-9);
assertEquals(0.7071067811865475, quaternion.getZ(), 1e-9);
assertEquals(0.7071067811865475, quaternion.getW(), 1e-9);
quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), -Math.PI / 2);
assertEquals(0, quaternion.getX(), 1e-9);
assertEquals(0, quaternion.getY(), 1e-9);
assertEquals(-0.7071067811865475, quaternion.getZ(), 1e-9);
assertEquals(0.7071067811865475, quaternion.getW(), 1e-9);
quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), 0.75 * Math.PI);
assertEquals(0, quaternion.getX(), 1e-9);
assertEquals(0, quaternion.getY(), 1e-9);
assertEquals(0.9238795325112867, quaternion.getZ(), 1e-9);
assertEquals(0.38268343236508984, quaternion.getW(), 1e-9);
quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), -0.75 * Math.PI);
assertEquals(0, quaternion.getX(), 1e-9);
assertEquals(0, quaternion.getY(), 1e-9);
assertEquals(-0.9238795325112867, quaternion.getZ(), 1e-9);
assertEquals(0.38268343236508984, quaternion.getW(), 1e-9);
quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), 1.5 * Math.PI);
assertEquals(0, quaternion.getX(), 1e-9);
assertEquals(0, quaternion.getY(), 1e-9);
assertEquals(0.7071067811865475, quaternion.getZ(), 1e-9);
assertEquals(-0.7071067811865475, quaternion.getW(), 1e-9);
}
@Test
public void testInvert() {
Quaternion inverse = Quaternion.fromAxisAngle(Vector3.zAxis(), Math.PI / 2).invert();
assertEquals(0, inverse.getX(), 1e-9);
assertEquals(0, inverse.getY(), 1e-9);
assertEquals(-0.7071067811865475, inverse.getZ(), 1e-9);
assertEquals(0.7071067811865475, inverse.getW(), 1e-9);
}
@Test
public void testMultiply() {
Quaternion quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), Math.PI / 2);
Quaternion inverse = quaternion.invert();
Quaternion rotated = quaternion.multiply(inverse);
assertEquals(1, rotated.getW(), 1e-9);
}
@Test
public void testRotateVector() {
Quaternion quaternion = Quaternion.fromAxisAngle(Vector3.zAxis(), Math.PI / 2);
Vector3 vector = new Vector3(1, 0, 0);
Vector3 rotated = quaternion.rotateAndScaleVector(vector);
assertEquals(0, rotated.getX(), 1e-9);
assertEquals(1, rotated.getY(), 1e-9);
assertEquals(0, rotated.getZ(), 1e-9);
}
}
/*
* Copyright (C) 2012 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_geometry;
import static org.junit.Assert.assertEquals;
import static org.junit.Assert.assertTrue;
import org.junit.Test;
import java.util.Random;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class TransformTest {
@Test
public void testMultiply() {
Transform transform1 = new Transform(Vector3.xAxis(), Quaternion.identity());
Transform transform2 =
new Transform(Vector3.yAxis(), Quaternion.fromAxisAngle(Vector3.zAxis(), Math.PI / 2));
Transform result1 = transform1.multiply(transform2);
assertEquals(1.0, result1.getTranslation().getX(), 1e-9);
assertEquals(1.0, result1.getTranslation().getY(), 1e-9);
assertEquals(0.0, result1.getTranslation().getZ(), 1e-9);
assertEquals(0.0, result1.getRotationAndScale().getX(), 1e-9);
assertEquals(0.0, result1.getRotationAndScale().getY(), 1e-9);
assertEquals(0.7071067811865475, result1.getRotationAndScale().getZ(), 1e-9);
assertEquals(0.7071067811865475, result1.getRotationAndScale().getW(), 1e-9);
Transform result2 = transform2.multiply(transform1);
assertEquals(0.0, result2.getTranslation().getX(), 1e-9);
assertEquals(2.0, result2.getTranslation().getY(), 1e-9);
assertEquals(0.0, result2.getTranslation().getZ(), 1e-9);
assertEquals(0.0, result2.getRotationAndScale().getX(), 1e-9);
assertEquals(0.0, result2.getRotationAndScale().getY(), 1e-9);
assertEquals(0.7071067811865475, result2.getRotationAndScale().getZ(), 1e-9);
assertEquals(0.7071067811865475, result2.getRotationAndScale().getW(), 1e-9);
}
@Test
public void testInvert() {
Transform transform =
new Transform(Vector3.yAxis(), Quaternion.fromAxisAngle(Vector3.zAxis(), Math.PI / 2));
Transform inverse = transform.invert();
assertEquals(-1.0, inverse.getTranslation().getX(), 1e-9);
assertEquals(0.0, inverse.getTranslation().getY(), 1e-9);
assertEquals(0.0, inverse.getTranslation().getZ(), 1e-9);
assertEquals(0.0, inverse.getRotationAndScale().getX(), 1e-9);
assertEquals(0.0, inverse.getRotationAndScale().getY(), 1e-9);
assertEquals(-0.7071067811865475, inverse.getRotationAndScale().getZ(), 1e-9);
assertEquals(0.7071067811865475, inverse.getRotationAndScale().getW(), 1e-9);
Transform neutral = transform.multiply(inverse);
assertTrue(neutral.almostEquals(Transform.identity(), 1e-9));
}
@Test
public void testInvertRandom() {
Random random = new Random();
random.setSeed(42);
for (int i = 0; i < 10000; i++) {
Vector3 vector = randomVector(random);
Quaternion quaternion = randomQuaternion(random);
Transform transform = new Transform(vector, quaternion);
Transform inverse = transform.invert();
Transform neutral = transform.multiply(inverse);
assertTrue(neutral.almostEquals(Transform.identity(), 1e-9));
}
}
@Test
public void testMultiplyRandom() {
Random random = new Random();
random.setSeed(42);
for (int i = 0; i < 10000; i++) {
Vector3 data = randomVector(random);
Vector3 vector1 = randomVector(random);
Vector3 vector2 = randomVector(random);
Quaternion quaternion1 = randomQuaternion(random);
Quaternion quaternion2 = randomQuaternion(random);
Transform transform1 = new Transform(vector1, quaternion1);
Transform transform2 = new Transform(vector2, quaternion2);
Vector3 result1 = transform1.apply(transform2.apply(data));
Vector3 result2 = transform1.multiply(transform2).apply(data);
assertTrue(result1.almostEquals(result2, 1e-9));
}
}
@Test
public void testScale() {
assertTrue(Vector3.xAxis().scale(2)
.almostEquals(Transform.identity().scale(2).apply(Vector3.xAxis()), 1e-9));
}
private Quaternion randomQuaternion(Random random) {
return new Quaternion(random.nextDouble(), random.nextDouble(), random.nextDouble(),
random.nextDouble());
}
private Vector3 randomVector(Random random) {
return new Vector3(random.nextDouble(), random.nextDouble(), random.nextDouble());
}
}
/*
* Copyright (C) 2012 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_geometry;
import static org.junit.Assert.assertEquals;
import org.junit.Test;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class Vector3Test {
@Test
public void testAdd() {
Vector3 vector1 = new Vector3(1, 2, 3);
Vector3 vector2 = new Vector3(2, 3, 4);
Vector3 result = vector1.add(vector2);
assertEquals(result.getX(), 3, 1e-9);
assertEquals(result.getY(), 5, 1e-9);
assertEquals(result.getZ(), 7, 1e-9);
}
@Test
public void testSubtract() {
Vector3 vector1 = new Vector3(1, 2, 3);
Vector3 vector2 = new Vector3(2, 3, 4);
Vector3 result = vector1.subtract(vector2);
assertEquals(result.getX(), -1, 1e-9);
assertEquals(result.getY(), -1, 1e-9);
assertEquals(result.getZ(), -1, 1e-9);
}
@Test
public void testInvert() {
Vector3 result = new Vector3(1, 1, 1).invert();
assertEquals(result.getX(), -1, 1e-9);
assertEquals(result.getY(), -1, 1e-9);
assertEquals(result.getZ(), -1, 1e-9);
}
@Test
public void testDotProduct() {
Vector3 vector1 = new Vector3(1, 2, 3);
Vector3 vector2 = new Vector3(2, 3, 4);
assertEquals(20.0, vector1.dotProduct(vector2), 1e-9);
}
@Test
public void testLength() {
assertEquals(2, new Vector3(2, 0, 0).getMagnitude(), 1e-9);
assertEquals(2, new Vector3(0, 2, 0).getMagnitude(), 1e-9);
assertEquals(2, new Vector3(0, 0, 2).getMagnitude(), 1e-9);
assertEquals(Math.sqrt(3), new Vector3(1, 1, 1).getMagnitude(), 1e-9);
}
}
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
apply plugin: 'application'
mainClassName = 'org.ros.RosRun'
dependencies {
compile project(':rosjava')
compile 'junit:junit:4.8.2'
}
#!/usr/bin/python
#
# Copyright (C) 2012 Google Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License"); you may not
# use this file except in compliance with the License. You may obtain a copy of
# the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
# License for the specific language governing permissions and limitations under
# the License.
"""Prints the serialized bytese of a nav_msgs.Odometry message in hex.
This can be modified slightly to print the serialized bytes in hex for
arbitrary ROS messages and is useful for generating test cases for rosjava
message serialization.
"""
__author__ = 'damonkohler@google.com (Damon Kohler)'
import StringIO
import roslib; roslib.load_manifest('rosjava_test')
import rospy
import nav_msgs.msg as nav_msgs
message = nav_msgs.Odometry()
buf = StringIO.StringIO()
message.serialize(buf)
print ''.join('0x%02x,' % ord(c) for c in buf.getvalue())[:-1]
/*
* Copyright (C) 2012 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros;
import nav_msgs.Odometry;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.ConnectedNode;
import org.ros.node.Node;
import org.ros.node.NodeMain;
import org.ros.node.topic.Publisher;
import org.ros.node.topic.Subscriber;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class MessageSerializationTestNode implements NodeMain {
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("message_serialization_test_node");
}
@Override
public void onStart(ConnectedNode connectedNode) {
final Publisher<nav_msgs.Odometry> publisher =
connectedNode.newPublisher("odom_echo", nav_msgs.Odometry._TYPE);
Subscriber<nav_msgs.Odometry> subscriber =
connectedNode.newSubscriber("odom", nav_msgs.Odometry._TYPE);
subscriber.addMessageListener(new MessageListener<Odometry>() {
@Override
public void onNewMessage(Odometry message) {
publisher.publish(message);
}
});
}
@Override
public void onShutdown(Node node) {
}
@Override
public void onShutdownComplete(Node node) {
}
@Override
public void onError(Node node, Throwable throwable) {
}
}
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros;
import org.apache.commons.logging.Log;
import org.ros.concurrent.CancellableLoop;
import org.ros.message.MessageFactory;
import org.ros.namespace.GraphName;
import org.ros.namespace.NameResolver;
import org.ros.node.AbstractNodeMain;
import org.ros.node.ConnectedNode;
import org.ros.node.parameter.ParameterTree;
import org.ros.node.topic.Publisher;
import java.util.List;
import java.util.Map;
/**
* This node is used in rostest end-to-end integration tests with other client
* libraries.
*
* @author kwc@willowgarage.com (Ken Conley)
*/
public class ParameterServerTestNode extends AbstractNodeMain {
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("rosjava/parameter_server_test_node");
}
@SuppressWarnings("rawtypes")
@Override
public void onStart(ConnectedNode connectedNode) {
final Publisher<std_msgs.String> pub_tilde =
connectedNode.newPublisher("tilde", std_msgs.String._TYPE);
final Publisher<std_msgs.String> pub_string =
connectedNode.newPublisher("string", std_msgs.String._TYPE);
final Publisher<std_msgs.Int64> pub_int =
connectedNode.newPublisher("int", std_msgs.Int64._TYPE);
final Publisher<std_msgs.Bool> pub_bool =
connectedNode.newPublisher("bool", std_msgs.Bool._TYPE);
final Publisher<std_msgs.Float64> pub_float =
connectedNode.newPublisher("float", std_msgs.Float64._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();
Log log = connectedNode.getLog();
MessageFactory topicMessageFactory = connectedNode.getTopicMessageFactory();
final std_msgs.String tilde_m = topicMessageFactory.newFromType(std_msgs.String._TYPE);
tilde_m.setData(param.getString(connectedNode.resolveName("~tilde").toString()));
log.info("tilde: " + tilde_m.getData());
GraphName paramNamespace = GraphName.of(param.getString("parameter_namespace"));
GraphName targetNamespace = GraphName.of(param.getString("target_namespace"));
log.info("parameter_namespace: " + paramNamespace);
log.info("target_namespace: " + targetNamespace);
NameResolver resolver = connectedNode.getResolver().newChild(paramNamespace);
NameResolver setResolver = connectedNode.getResolver().newChild(targetNamespace);
final std_msgs.String string_m = topicMessageFactory.newFromType(std_msgs.String._TYPE);
string_m.setData(param.getString(resolver.resolve("string")));
log.info("string: " + string_m.getData());
final std_msgs.Int64 int_m = topicMessageFactory.newFromType(std_msgs.Int64._TYPE);
int_m.setData(param.getInteger(resolver.resolve("int")));
log.info("int: " + int_m.getData());
final std_msgs.Bool bool_m = topicMessageFactory.newFromType(std_msgs.Bool._TYPE);
bool_m.setData(param.getBoolean(resolver.resolve("bool")));
log.info("bool: " + bool_m.getData());
final std_msgs.Float64 float_m = topicMessageFactory.newFromType(std_msgs.Float64._TYPE);
float_m.setData(param.getDouble(resolver.resolve("float")));
log.info("float: " + float_m.getData());
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"));
composite_m.getA().setY((Double) ((Map) composite_map.get("a")).get("y"));
composite_m.getA().setZ((Double) ((Map) composite_map.get("a")).get("z"));
composite_m.getB().setX((Double) ((Map) composite_map.get("b")).get("x"));
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 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"));
int[] data = new int[list.size()];
for (int i = 0; i < list.size(); i++) {
data[i] = list.get(i);
}
list_m.setInt32Array(data);
// Set parameters
param.set(setResolver.resolve("string"), string_m.getData());
param.set(setResolver.resolve("int"), (int) int_m.getData());
param.set(setResolver.resolve("float"), float_m.getData());
param.set(setResolver.resolve("bool"), bool_m.getData());
param.set(setResolver.resolve("composite"), composite_map);
param.set(setResolver.resolve("list"), list);
connectedNode.executeCancellableLoop(new CancellableLoop() {
@Override
protected void loop() throws InterruptedException {
pub_tilde.publish(tilde_m);
pub_string.publish(string_m);
pub_int.publish(int_m);
pub_bool.publish(bool_m);
pub_float.publish(float_m);
pub_composite.publish(composite_m);
pub_list.publish(list_m);
Thread.sleep(100);
}
});
}
}
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.AbstractNodeMain;
import org.ros.node.ConnectedNode;
import org.ros.node.topic.Publisher;
import org.ros.node.topic.Subscriber;
/**
* This node is used in rostest end-to-end integration tests with other client
* libraries.
*
* @author kwc@willowgarage.com (Ken Conley)
*/
public class PassthroughTestNode extends AbstractNodeMain {
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("rosjava/passthrough_test_node");
}
@Override
public void onStart(final ConnectedNode connectedNode) {
// The goal of the passthrough node is simply to retransmit the messages
// sent to it. This allows us to external verify that the node is compatible
// with multiple publishers, multiple subscribers, etc...
// String pass through
final Publisher<std_msgs.String> pub_string =
connectedNode.newPublisher("string_out", std_msgs.String._TYPE);
MessageListener<std_msgs.String> string_cb = new MessageListener<std_msgs.String>() {
@Override
public void onNewMessage(std_msgs.String m) {
pub_string.publish(m);
}
};
Subscriber<std_msgs.String> stringSubscriber =
connectedNode.newSubscriber("string_in", "std_msgs/String");
stringSubscriber.addMessageListener(string_cb);
// Int64 pass through
final Publisher<std_msgs.Int64> pub_int64 = connectedNode.newPublisher("int64_out", "std_msgs/Int64");
MessageListener<std_msgs.Int64> int64_cb = new MessageListener<std_msgs.Int64>() {
@Override
public void onNewMessage(std_msgs.Int64 m) {
pub_int64.publish(m);
}
};
Subscriber<std_msgs.Int64> int64Subscriber = connectedNode.newSubscriber("int64_in", "std_msgs/Int64");
int64Subscriber.addMessageListener(int64_cb);
// TestHeader pass through
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(rosjava_test_msgs.TestHeader m) {
m.setOrigCallerId(m.getCallerId());
m.setCallerId(connectedNode.getName().toString());
pub_header.publish(m);
}
};
Subscriber<rosjava_test_msgs.TestHeader> testHeaderSubscriber =
connectedNode.newSubscriber("test_header_in", "rosjava_test_msgs/TestHeader");
testHeaderSubscriber.addMessageListener(header_cb);
// TestComposite pass through
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(rosjava_test_msgs.Composite m) {
pub_composite.publish(m);
}
};
Subscriber<rosjava_test_msgs.Composite> compositeSubscriber =
connectedNode.newSubscriber("composite_in", "rosjava_test_msgs/Composite");
compositeSubscriber.addMessageListener(composite_cb);
}
}
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros;
import org.ros.concurrent.CancellableLoop;
import org.ros.message.MessageFactory;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.AbstractNodeMain;
import org.ros.node.ConnectedNode;
import org.ros.node.topic.Publisher;
import org.ros.node.topic.Subscriber;
/**
* This node is used to test the slave API externally using rostest.
*
* @author kwc@willowgarage.com (Ken Conley)
*/
public class SlaveApiTestNode extends AbstractNodeMain {
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("rosjava/slave_api_test_node");
}
@Override
public void onStart(final ConnectedNode connectedNode) {
// Basic chatter in/out test.
final Publisher<std_msgs.String> pub_string =
connectedNode.newPublisher("chatter_out", std_msgs.String._TYPE);
MessageListener<std_msgs.String> chatter_cb = new MessageListener<std_msgs.String>() {
@Override
public void onNewMessage(std_msgs.String m) {
System.out.println("String: " + m.getData());
}
};
Subscriber<std_msgs.String> stringSubscriber =
connectedNode.newSubscriber("chatter_in", std_msgs.String._TYPE);
stringSubscriber.addMessageListener(chatter_cb);
// Have at least one case of dual pub/sub on the same topic.
final Publisher<std_msgs.Int64> pub_int64_pubsub =
connectedNode.newPublisher("int64", std_msgs.Int64._TYPE);
MessageListener<std_msgs.Int64> int64_cb = new MessageListener<std_msgs.Int64>() {
@Override
public void onNewMessage(std_msgs.Int64 m) {
}
};
Subscriber<std_msgs.Int64> int64Subscriber =
connectedNode.newSubscriber("int64", "std_msgs/std_msgs.Int64");
int64Subscriber.addMessageListener(int64_cb);
// Don't do any performance optimizations here. We want to make sure that
// GC, etc. is working.
connectedNode.executeCancellableLoop(new CancellableLoop() {
@Override
protected void loop() throws InterruptedException {
MessageFactory topicMessageFactory = connectedNode.getTopicMessageFactory();
std_msgs.String chatter = topicMessageFactory.newFromType(std_msgs.String._TYPE);
chatter.setData("hello " + System.currentTimeMillis());
pub_string.publish(chatter);
std_msgs.Int64 num = topicMessageFactory.newFromType(std_msgs.Int64._TYPE);
num.setData(1);
pub_int64_pubsub.publish(num);
Thread.sleep(100);
}
});
}
}
java_binary(
name = "rosjava_tutorial_pubsub",
srcs = glob([
"src/main/**/*.java",
]),
main_class = "org.ros.RosRun",
deps = [
"//3rdparty/jvm/org/apache/commons:com_springsource_org_apache_commons_logging",
"//3rdparty/jvm/org/ros/rosjava_messages:std_msgs",
"//rosjava",
"@com_github_rosjava_rosjava_bootstrap//message_generation",
],
)
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
apply plugin: 'application'
mainClassName = 'org.ros.RosRun'
dependencies {
compile project(':rosjava')
}
defaultTasks 'publish', 'installDist'
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_tutorial_pubsub;
import org.apache.commons.logging.Log;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.AbstractNodeMain;
import org.ros.node.ConnectedNode;
import org.ros.node.NodeMain;
import org.ros.node.topic.Subscriber;
/**
* A simple {@link Subscriber} {@link NodeMain}.
*
* @author damonkohler@google.com (Damon Kohler)
*/
public class Listener extends AbstractNodeMain {
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("rosjava_tutorial_pubsub/listener");
}
@Override
public void onStart(ConnectedNode connectedNode) {
final Log log = connectedNode.getLog();
Subscriber<std_msgs.String> subscriber = connectedNode.newSubscriber("chatter", std_msgs.String._TYPE);
subscriber.addMessageListener(new MessageListener<std_msgs.String>() {
@Override
public void onNewMessage(std_msgs.String message) {
log.info("I heard: \"" + message.getData() + "\"");
}
});
}
}
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_tutorial_pubsub;
import org.ros.concurrent.CancellableLoop;
import org.ros.namespace.GraphName;
import org.ros.node.AbstractNodeMain;
import org.ros.node.ConnectedNode;
import org.ros.node.NodeMain;
import org.ros.node.topic.Publisher;
/**
* A simple {@link Publisher} {@link NodeMain}.
*
* @author damonkohler@google.com (Damon Kohler)
*/
public class Talker extends AbstractNodeMain {
private String topic_name;
public Talker() {
topic_name = "chatter";
}
public Talker(String topic)
{
topic_name = topic;
}
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("rosjava_tutorial_pubsub/talker");
}
@Override
public void onStart(final ConnectedNode connectedNode) {
final Publisher<std_msgs.String> publisher =
connectedNode.newPublisher(topic_name, std_msgs.String._TYPE);
// This CancellableLoop will be canceled automatically when the node shuts
// down.
connectedNode.executeCancellableLoop(new CancellableLoop() {
private int sequenceNumber;
@Override
protected void setup() {
sequenceNumber = 0;
}
@Override
protected void loop() throws InterruptedException {
std_msgs.String str = publisher.newMessage();
str.setData("Hello world! " + sequenceNumber);
publisher.publish(str);
sequenceNumber++;
Thread.sleep(1000);
}
});
}
}
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
apply plugin: 'application'
mainClassName = 'org.ros.RosRun'
dependencies {
compile project(':rosjava')
compile 'org.ros.rosjava_messages:sensor_msgs:[1.12,1.13)'
}
/*
* Copyright (C) 2012 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_tutorial_right_hand_rule;
import org.ros.message.MessageListener;
import org.ros.namespace.GraphName;
import org.ros.node.AbstractNodeMain;
import org.ros.node.ConnectedNode;
import org.ros.node.topic.Publisher;
import org.ros.node.topic.Subscriber;
/**
* @author damonkohler@google.com (Damon Kohler)
*/
public class RightHandRule extends AbstractNodeMain {
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("right_hand_rule");
}
@Override
public void onStart(ConnectedNode connectedNode) {
final Publisher<geometry_msgs.Twist> publisher =
connectedNode.newPublisher("cmd_vel", geometry_msgs.Twist._TYPE);
final geometry_msgs.Twist twist = publisher.newMessage();
final Subscriber<sensor_msgs.LaserScan> subscriber =
connectedNode.newSubscriber("base_scan", sensor_msgs.LaserScan._TYPE);
subscriber.addMessageListener(new MessageListener<sensor_msgs.LaserScan>() {
@Override
public void onNewMessage(sensor_msgs.LaserScan message) {
float[] ranges = message.getRanges();
float northRange = ranges[ranges.length / 2];
float northEastRange = ranges[ranges.length / 3];
double linearVelocity = 0.5;
double angularVelocity = -0.5;
if (northRange < 1. || northEastRange < 1.) {
linearVelocity = 0;
angularVelocity = 0.5;
}
twist.getAngular().setZ(angularVelocity);
twist.getLinear().setX(linearVelocity);
publisher.publish(twist);
}
});
}
}
define topurg ranger
(
sensor(
range [ 0.0 30.0 ]
fov 270.25
samples 1081
)
# generic model properties
color "black"
size [ 0.05 0.05 0.1 ]
)
define erratic position
(
size [0.35 0.35 0.25]
origin [-0.05 0 0 0]
gui_nose 1
drive "diff"
topurg(pose [ 0.050 0.000 0 0.000 ])
)
define floorplan model
(
# sombre, sensible, artistic
color "gray30"
# most maps will need a bounding box
boundary 0
gui_nose 0
gui_grid 0
gui_outline 0
gripper_return 0
fiducial_return 0
laser_return 1
)
# set the resolution of the underlying raytrace model in meters
resolution 0.02
interval_sim 100 # simulation timestep in milliseconds
window
(
size [ 500.0 500.0 ]
rotate [ 0.0 0.0 ]
scale 10.0
)
# load an environment bitmap
floorplan
(
name "maze"
bitmap "maze.png"
size [50.0 50.0 0.5]
pose [ 0.0 0.0 0 0.0 ]
gui_move 0
)
# throw in a robot
erratic( pose [ 1.25 -25.0 0.0 90.0 ] name "era" color "blue")
rosjava_tutorial_right_hand_rule/world/maze.png

6.93 KiB

/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
apply plugin: 'application'
mainClassName = 'org.ros.RosRun'
dependencies {
compile project(':rosjava')
}
/*
* Copyright (C) 2011 Google Inc.
*
* Licensed under the Apache License, Version 2.0 (the "License"); you may not
* use this file except in compliance with the License. You may obtain a copy of
* the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations under
* the License.
*/
package org.ros.rosjava_tutorial_services;
import org.ros.exception.RemoteException;
import org.ros.exception.RosRuntimeException;
import org.ros.exception.ServiceNotFoundException;
import org.ros.namespace.GraphName;
import org.ros.node.AbstractNodeMain;
import org.ros.node.ConnectedNode;
import org.ros.node.NodeMain;
import org.ros.node.service.ServiceClient;
import org.ros.node.service.ServiceResponseListener;
/**
* A simple {@link ServiceClient} {@link NodeMain}.
*
* @author damonkohler@google.com (Damon Kohler)
*/
public class Client extends AbstractNodeMain {
@Override
public GraphName getDefaultNodeName() {
return GraphName.of("rosjava_tutorial_services/client");
}
@Override
public void onStart(final ConnectedNode connectedNode) {
ServiceClient<rosjava_test_msgs.AddTwoIntsRequest, rosjava_test_msgs.AddTwoIntsResponse> serviceClient;
try {
serviceClient = connectedNode.newServiceClient("add_two_ints", rosjava_test_msgs.AddTwoInts._TYPE);
} catch (ServiceNotFoundException e) {
throw new RosRuntimeException(e);
}
final rosjava_test_msgs.AddTwoIntsRequest request = serviceClient.newMessage();
request.setA(2);
request.setB(2);
serviceClient.call(request, new ServiceResponseListener<rosjava_test_msgs.AddTwoIntsResponse>() {
@Override
public void onSuccess(rosjava_test_msgs.AddTwoIntsResponse response) {
connectedNode.getLog().info(
String.format("%d + %d = %d", request.getA(), request.getB(), response.getSum()));
}
@Override
public void onFailure(RemoteException e) {
throw new RosRuntimeException(e);
}
});
}
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment