diff --git a/message_generation_tests/build.gradle b/message_generation_tests/build.gradle new file mode 100644 index 0000000000000000000000000000000000000000..2d053391fd8e04c8e175c94b1e790be03da064ef --- /dev/null +++ b/message_generation_tests/build.gradle @@ -0,0 +1,39 @@ +/* + * 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. + */ + +version='0.1.0' + +dependencies { + compile 'org.ros.rosjava_messages:rosjava_test_msgs:0.1.+' + compile 'org.ros.rosjava_bootstrap:message_generation:0.1.+' + testCompile 'junit:junit:4.8.2' +} +jar { + manifest { + version = project.version + symbolicName = 'org.ros.rosjava_core.message_generation_tests' + } +} + +/* + * Ugly hack to stop osgi/java plugin combination from barfing + * when there are no sources. + */ +task bugfixtask << { + mkdir sourceSets.main.output.classesDir +} + +jar.dependsOn(bugfixtask) diff --git a/message_generation_tests/src/test/java/org/ros/internal/message/Md5GeneratorTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/Md5GeneratorTest.java new file mode 100644 index 0000000000000000000000000000000000000000..6746f86b59aa2d24fb765a33ef456619840f05ca --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/internal/message/Md5GeneratorTest.java @@ -0,0 +1,108 @@ +/* + * 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.internal.message; + +import static org.junit.Assert.assertEquals; + +import org.ros.internal.message.definition.MessageDefinitionProviderChain; + +import org.junit.Before; +import org.junit.Test; +import org.ros.internal.message.service.ServiceDefinitionResourceProvider; +import org.ros.internal.message.service.ServiceDescription; +import org.ros.internal.message.service.ServiceDescriptionFactory; +import org.ros.internal.message.topic.TopicDefinitionResourceProvider; +import org.ros.internal.message.topic.TopicDescription; +import org.ros.internal.message.topic.TopicDescriptionFactory; + +/** + * @author damonkohler@google.com (Damon Kohler) + */ +public class Md5GeneratorTest { + + private TopicDescriptionFactory topicDescriptionFactory; + private ServiceDescriptionFactory serviceDescriptionFactory; + + @Before + public void setUp() { + MessageDefinitionProviderChain messageDefinitionProviderChain = + new MessageDefinitionProviderChain(); + messageDefinitionProviderChain + .addMessageDefinitionProvider(new TopicDefinitionResourceProvider()); + messageDefinitionProviderChain + .addMessageDefinitionProvider(new ServiceDefinitionResourceProvider()); + topicDescriptionFactory = new TopicDescriptionFactory(messageDefinitionProviderChain); + serviceDescriptionFactory = new ServiceDescriptionFactory(messageDefinitionProviderChain); + } + + @Test + public void testPrimitives() { + TopicDescription topicDescription = + topicDescriptionFactory.newFromType("rosjava_test_msgs/TestPrimitives"); + assertEquals("3e70f428a22c0d26ca67f87802c8e00f", topicDescription.getMd5Checksum()); + } + + @Test + public void testString() { + TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/TestString"); + assertEquals("334ff4377be93faa44ebc66d23d40fd3", topicDescription.getMd5Checksum()); + } + + @Test + public void testHeader() { + TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/TestHeader"); + assertEquals("4b5a00f536da2f756ba6aebcf795a967", topicDescription.getMd5Checksum()); + } + + @Test + public void testArrays() { + TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/TestArrays"); + assertEquals("4cc9b5e2cebe791aa3e994f5bc159eb6", topicDescription.getMd5Checksum()); + } + + @Test + public void testComposite() { + TopicDescription topicDescription = topicDescriptionFactory.newFromType("rosjava_test_msgs/Composite"); + assertEquals("d8fb6eb869ad3956b50e8737d96dc9fa", topicDescription.getMd5Checksum()); + } + + @Test + public void testOdometry() { + TopicDescription topicDescription = topicDescriptionFactory.newFromType("nav_msgs/Odometry"); + assertEquals("cd5e73d190d741a2f92e81eda573aca7", topicDescription.getMd5Checksum()); + } + + @Test + public void testEmpty() { + ServiceDescription serviceDescription = serviceDescriptionFactory.newFromType("std_srvs/Empty"); + assertEquals("d41d8cd98f00b204e9800998ecf8427e", serviceDescription.getMd5Checksum()); + } + + @Test + public void testAddTwoInts() { + ServiceDescription serviceDescription = + serviceDescriptionFactory.newFromType("rosjava_test_msgs/AddTwoInts"); + assertEquals("6a2e34150c00229791cc89ff309fff21", serviceDescription.getMd5Checksum()); + } + + @Test + public void testTransitiveSrv() { + ServiceDescription serviceDescription = + serviceDescriptionFactory.newFromType("rosjava_test_msgspy/TransitiveSrv"); + assertEquals("8b7918ee2b81eaf825f4c70de011f6fa", serviceDescription.getMd5Checksum()); + } +} diff --git a/message_generation_tests/src/test/java/org/ros/internal/message/MessageInterfaceBuilderTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/MessageInterfaceBuilderTest.java new file mode 100644 index 0000000000000000000000000000000000000000..38e5316113765c178b347e9eaf82872e4e7a489b --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/internal/message/MessageInterfaceBuilderTest.java @@ -0,0 +1,55 @@ +/* + * 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.internal.message; + +import static org.junit.Assert.assertEquals; + +import org.junit.Before; +import org.junit.Test; +import org.ros.internal.message.topic.TopicDefinitionResourceProvider; +import org.ros.message.MessageDeclaration; +import org.ros.message.MessageFactory; + +/** + * @author damonkohler@google.com (Damon Kohler) + */ +public class MessageInterfaceBuilderTest { + + private TopicDefinitionResourceProvider topicDefinitionResourceProvider; + private MessageFactory messageFactory; + + @Before + public void before() { + topicDefinitionResourceProvider = new TopicDefinitionResourceProvider(); + messageFactory = new DefaultMessageFactory(topicDefinitionResourceProvider); + } + + @Test + public void testDuplicateFieldNames() { + MessageInterfaceBuilder builder = new MessageInterfaceBuilder(); + builder.setPackageName("foo"); + builder.setInterfaceName("bar"); + builder.setMessageDeclaration(MessageDeclaration.of("foo/bar", "int32 foo\nint32 Foo")); + builder.setAddConstantsAndMethods(true); + String result = builder.build(messageFactory); + assertEquals("package foo;\n\n" + + "public interface bar extends org.ros.internal.message.Message {\n" + + " static final java.lang.String _TYPE = \"foo/bar\";\n" + + " static final java.lang.String _DEFINITION = \"int32 foo\\nint32 Foo\";\n" + + " int getFoo();\n" + " void setFoo(int value);\n" + "}\n", result); + } +} diff --git a/message_generation_tests/src/test/java/org/ros/internal/message/MessageTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/MessageTest.java new file mode 100644 index 0000000000000000000000000000000000000000..fe80bb483e139b811229ddf2453e02abcc866e22 --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/internal/message/MessageTest.java @@ -0,0 +1,124 @@ +/* + * 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.internal.message; + +import static org.junit.Assert.assertEquals; + +import com.google.common.collect.Lists; + +import org.junit.Before; +import org.junit.Test; +import org.ros.internal.message.topic.TopicDefinitionResourceProvider; +import org.ros.message.MessageFactory; + +/** + * @author damonkohler@google.com (Damon Kohler) + */ +public class MessageTest { + + private TopicDefinitionResourceProvider topicDefinitionResourceProvider; + private MessageFactory messageFactory; + + @Before + public void before() { + topicDefinitionResourceProvider = new TopicDefinitionResourceProvider(); + messageFactory = new DefaultMessageFactory(topicDefinitionResourceProvider); + } + + @Test + public void testCreateEmptyMessage() { + topicDefinitionResourceProvider.add("foo/foo", ""); + messageFactory.newFromType("foo/foo"); + } + + @Test + public void testCreateEmptyMessageWithBlankLines() { + topicDefinitionResourceProvider.add("foo/foo", "\n\n\n\n\n"); + messageFactory.newFromType("foo/foo"); + } + + @Test + public void testString() { + String data = "Hello, ROS!"; + RawMessage rawMessage = messageFactory.newFromType("std_msgs/String"); + rawMessage.setString("data", data); + assertEquals(data, rawMessage.getString("data")); + } + + @Test + public void testStringWithComments() { + topicDefinitionResourceProvider.add("foo/foo", "# foo\nstring data\n # string other data"); + String data = "Hello, ROS!"; + RawMessage rawMessage = messageFactory.newFromType("foo/foo"); + rawMessage.setString("data", data); + assertEquals(data, rawMessage.getString("data")); + } + + @Test + public void testInt8() { + byte data = 42; + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Int8"); + rawMessage.setInt8("data", data); + assertEquals(data, rawMessage.getInt8("data")); + } + + @Test + public void testNestedMessage() { + topicDefinitionResourceProvider.add("foo/foo", "bar data"); + topicDefinitionResourceProvider.add("foo/bar", "int8 data"); + RawMessage fooMessage = messageFactory.newFromType("foo/foo"); + RawMessage barMessage = messageFactory.newFromType("foo/bar"); + fooMessage.setMessage("data", barMessage); + byte data = 42; + barMessage.setInt8("data", data); + assertEquals(data, fooMessage.getMessage("data").toRawMessage().getInt8("data")); + } + + @Test + public void testNestedMessageList() { + topicDefinitionResourceProvider.add("foo/foo", "bar[] data"); + topicDefinitionResourceProvider.add("foo/bar", "int8 data"); + RawMessage fooMessage = messageFactory.newFromType("foo/foo"); + RawMessage barMessage = messageFactory.newFromType("foo/bar"); + fooMessage.setMessageList("data", Lists.<Message>newArrayList(barMessage)); + byte data = 42; + barMessage.toRawMessage().setInt8("data", data); + assertEquals(data, fooMessage.getMessageList("data").get(0).toRawMessage().getInt8("data")); + } + + @Test + public void testConstantInt8() { + topicDefinitionResourceProvider.add("foo/foo", "int8 data=42"); + RawMessage rawMessage = messageFactory.newFromType("foo/foo"); + assertEquals(42, rawMessage.getInt8("data")); + } + + @Test + public void testConstantString() { + topicDefinitionResourceProvider.add("foo/foo", "string data=Hello, ROS! # comment "); + RawMessage rawMessage = messageFactory.newFromType("foo/foo"); + assertEquals("Hello, ROS! # comment", rawMessage.getString("data")); + } + + public void testInt8List() { + topicDefinitionResourceProvider.add("foo/foo", "int8[] data"); + RawMessage rawMessage = messageFactory.newFromType("foo/foo"); + byte[] data = new byte[] { (byte) 1, (byte) 2, (byte) 3 }; + rawMessage.setInt8Array("data", data); + assertEquals(data, rawMessage.getInt8Array("data")); + } +} \ No newline at end of file diff --git a/message_generation_tests/src/test/java/org/ros/internal/message/RawMessageSerializationTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/RawMessageSerializationTest.java new file mode 100644 index 0000000000000000000000000000000000000000..d5bf1bbce7e81cec0c1aca33b8bab7331d3eee6b --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/internal/message/RawMessageSerializationTest.java @@ -0,0 +1,203 @@ +/* + * 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.internal.message; + +import static org.junit.Assert.assertTrue; + +import com.google.common.collect.Lists; + +import org.jboss.netty.buffer.ChannelBuffer; +import org.junit.Before; +import org.junit.Test; +import org.ros.internal.message.topic.TopicDefinitionResourceProvider; +import org.ros.message.Duration; +import org.ros.message.MessageFactory; +import org.ros.message.Time; + +/** + * @author damonkohler@google.com (Damon Kohler) + */ +public class RawMessageSerializationTest { + + private TopicDefinitionResourceProvider topicDefinitionResourceProvider; + private MessageFactory messageFactory; + + @Before + public void before() { + topicDefinitionResourceProvider = new TopicDefinitionResourceProvider(); + messageFactory = new DefaultMessageFactory(topicDefinitionResourceProvider); + } + + private void checkSerializeAndDeserialize(Message message) { + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + DefaultMessageSerializer serializer = new DefaultMessageSerializer(); + serializer.serialize(message, buffer); + DefaultMessageDeserializer<RawMessage> deserializer = + new DefaultMessageDeserializer<RawMessage>(message.toRawMessage().getIdentifier(), + messageFactory); + RawMessage deserializedMessage = deserializer.deserialize(buffer); + assertTrue(message.equals(deserializedMessage)); + } + + @Test + public void testBool() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Bool"); + rawMessage.setBool("data", true); + checkSerializeAndDeserialize(rawMessage); + rawMessage.setBool("data", false); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testInt8() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Int8"); + rawMessage.setInt8("data", (byte) 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testUint8() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/UInt8"); + rawMessage.setUInt8("data", (byte) 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testInt16() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Int16"); + rawMessage.setInt16("data", (short) 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testUInt16() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/UInt16"); + rawMessage.setUInt16("data", (short) 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testInt32() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Int32"); + rawMessage.setInt32("data", 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testUInt32() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/UInt32"); + rawMessage.setUInt32("data", 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testInt64() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Int64"); + rawMessage.setInt64("data", 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testUInt64() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/UInt64"); + rawMessage.setUInt64("data", 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testFloat32() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Float32"); + rawMessage.setFloat32("data", 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testFloat64() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Float64"); + rawMessage.setFloat64("data", 42); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testString() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/String"); + rawMessage.setString("data", "Hello, ROS!"); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testTime() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Time"); + rawMessage.setTime("data", new Time()); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testDuration() { + RawMessage rawMessage = messageFactory.newFromType("std_msgs/Duration"); + rawMessage.setDuration("data", new Duration()); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testNestedMessage() { + topicDefinitionResourceProvider.add("foo/foo", "std_msgs/String data"); + RawMessage fooMessage = messageFactory.newFromType("foo/foo"); + RawMessage stringMessage = messageFactory.newFromType("std_msgs/String"); + stringMessage.setString("data", "Hello, ROS!"); + fooMessage.setMessage("data", stringMessage); + checkSerializeAndDeserialize(fooMessage); + } + + @Test + public void testNestedMessageArray() { + topicDefinitionResourceProvider.add("foo/foo", "std_msgs/String[] data"); + RawMessage fooMessage = messageFactory.newFromType("foo/foo"); + RawMessage stringMessageA = messageFactory.newFromType("std_msgs/String"); + stringMessageA.setString("data", "Hello, ROS!"); + RawMessage stringMessageB = messageFactory.newFromType("std_msgs/String"); + stringMessageB.setString("data", "Goodbye, ROS!"); + fooMessage.setMessageList("data", Lists.<Message>newArrayList(stringMessageA, stringMessageB)); + checkSerializeAndDeserialize(fooMessage); + } + + @Test + public void testChannelBuffer() { + topicDefinitionResourceProvider.add("foo/foo", "uint8[] data"); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + buffer.writeBytes(new byte[] { 1, 2, 3, 4, 5 }); + RawMessage rawMessage = messageFactory.newFromType("foo/foo"); + rawMessage.setChannelBuffer("data", buffer); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testInt32Array() { + topicDefinitionResourceProvider.add("foo/foo", "int32[] data"); + RawMessage rawMessage = messageFactory.newFromType("foo/foo"); + rawMessage.setInt32Array("data", new int[] { 1, 2, 3, 4, 5 }); + checkSerializeAndDeserialize(rawMessage); + } + + @Test + public void testFloat64Array() { + topicDefinitionResourceProvider.add("foo/foo", "float64[] data"); + RawMessage rawMessage = messageFactory.newFromType("foo/foo"); + rawMessage.setFloat64Array("data", new double[] { 1, 2, 3, 4, 5 }); + checkSerializeAndDeserialize(rawMessage); + } +} diff --git a/message_generation_tests/src/test/java/org/ros/internal/message/ServiceTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/ServiceTest.java new file mode 100644 index 0000000000000000000000000000000000000000..decb7c333b0353dedd3c8f61a74ec3dec95acaca --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/internal/message/ServiceTest.java @@ -0,0 +1,51 @@ +/* + * 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.internal.message; + +import org.junit.Before; +import org.junit.Test; +import org.ros.internal.message.service.ServiceDefinitionResourceProvider; +import org.ros.internal.message.service.ServiceRequestMessageFactory; +import org.ros.internal.message.service.ServiceResponseMessageFactory; + +/** + * @author damonkohler@google.com (Damon Kohler) + */ +public class ServiceTest { + + private ServiceDefinitionResourceProvider serviceDefinitionResourceProvider; + private ServiceRequestMessageFactory serviceRequestMessageFactory; + private ServiceResponseMessageFactory serviceResponseMessageFactory; + + @Before + public void setUp() { + serviceDefinitionResourceProvider = new ServiceDefinitionResourceProvider(); + serviceDefinitionResourceProvider.add("foo/Echo", "string data\n---\nstring data"); + serviceRequestMessageFactory = + new ServiceRequestMessageFactory(serviceDefinitionResourceProvider); + serviceResponseMessageFactory = + new ServiceResponseMessageFactory(serviceDefinitionResourceProvider); + } + + @Test + public void testCreateEchoService() { + RawMessage request = serviceRequestMessageFactory.newFromType("foo/Echo"); + RawMessage response = serviceResponseMessageFactory.newFromType("foo/Echo"); + request.setString("data", "Hello, ROS!"); + response.setString("data", "Hello, ROS!"); + } +} diff --git a/message_generation_tests/src/test/java/org/ros/internal/message/field/ArrayFieldTest.java b/message_generation_tests/src/test/java/org/ros/internal/message/field/ArrayFieldTest.java new file mode 100644 index 0000000000000000000000000000000000000000..7ebb26489cd77a1c252685904b056e97e742b6b9 --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/internal/message/field/ArrayFieldTest.java @@ -0,0 +1,272 @@ +/* + * 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.internal.message.field; + +import static org.junit.Assert.assertArrayEquals; +import static org.junit.Assert.assertEquals; + +import org.ros.internal.message.MessageBuffers; + +import org.jboss.netty.buffer.ChannelBuffer; +import org.junit.Test; + +/** + * The following unit tests were created by inspecting the serialization of + * array fields using the ROS Python client library. + * + * @author damonkohler@google.com (Damon Kohler) + */ +public class ArrayFieldTest { + + @Test + public void testBooleanArrayFieldVariableSize() { + BooleanArrayField field = BooleanArrayField.newVariable("foo", -1); + boolean[] value = new boolean[] { true, false, true, false }; + field.setValue(value); + assertEquals(PrimitiveFieldType.BOOL, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 4, 0, 0, 0, 1, 0, 1, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testBooleanArrayFieldFixedSize() { + BooleanArrayField field = BooleanArrayField.newVariable("foo", 4); + field.setValue(new boolean[] { true, false, true, false }); + assertEquals(PrimitiveFieldType.BOOL, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 1, 0, 1, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @SuppressWarnings("deprecation") + @Test + public void testByteArrayFieldVariableSize() { + testByteArrayFieldVariableSize(PrimitiveFieldType.INT8); + testByteArrayFieldVariableSize(PrimitiveFieldType.BYTE); + testByteArrayFieldVariableSize(PrimitiveFieldType.UINT8); + testByteArrayFieldVariableSize(PrimitiveFieldType.CHAR); + } + + private void testByteArrayFieldVariableSize(FieldType type) { + ByteArrayField field = ByteArrayField.newVariable(type, "foo", -1); + field.setValue(new byte[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 4, 0, 0, 0, 1, 2, 3, 4 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @SuppressWarnings("deprecation") + @Test + public void testByteArrayFieldFixedSize() { + testByteArrayFieldFixedSize(PrimitiveFieldType.INT8); + testByteArrayFieldFixedSize(PrimitiveFieldType.BYTE); + testByteArrayFieldFixedSize(PrimitiveFieldType.UINT8); + testByteArrayFieldFixedSize(PrimitiveFieldType.CHAR); + } + + private void testByteArrayFieldFixedSize(FieldType type) { + ByteArrayField field = ByteArrayField.newVariable(type, "foo", 4); + field.setValue(new byte[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 1, 2, 3, 4 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testDoubleArrayFieldVariableSize() { + DoubleArrayField field = DoubleArrayField.newVariable("foo", -1); + field.setValue(new double[] { 1, 2, 3, 4 }); + assertEquals(PrimitiveFieldType.FLOAT64, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = + new byte[] { 4, 0, 0, 0, 0, 0, 0, 0, 0, 0, -16, 63, 0, 0, 0, 0, 0, 0, 0, 64, 0, 0, 0, 0, 0, + 0, 8, 64, 0, 0, 0, 0, 0, 0, 16, 64 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testDoubleArrayFieldFixedSize() { + DoubleArrayField field = DoubleArrayField.newVariable("foo", 4); + field.setValue(new double[] { 1, 2, 3, 4 }); + assertEquals(PrimitiveFieldType.FLOAT64, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = + new byte[] { 0, 0, 0, 0, 0, 0, -16, 63, 0, 0, 0, 0, 0, 0, 0, 64, 0, 0, 0, 0, 0, 0, 8, 64, + 0, 0, 0, 0, 0, 0, 16, 64 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testFloatArrayFieldVariableSize() { + FloatArrayField field = FloatArrayField.newVariable("foo", -1); + field.setValue(new float[] { 1, 2, 3, 4 }); + assertEquals(PrimitiveFieldType.FLOAT32, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = + new byte[] { 4, 0, 0, 0, 0, 0, -128, 63, 0, 0, 0, 64, 0, 0, 64, 64, 0, 0, -128, 64 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testFloatArrayFieldFixedSize() { + FloatArrayField field = FloatArrayField.newVariable("foo", 4); + field.setValue(new float[] { 1, 2, 3, 4 }); + assertEquals(PrimitiveFieldType.FLOAT32, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 0, 0, -128, 63, 0, 0, 0, 64, 0, 0, 64, 64, 0, 0, -128, 64 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testIntegerArrayFieldVariableSize() { + testIntegerArrayFieldVariableSize(PrimitiveFieldType.INT32); + testIntegerArrayFieldVariableSize(PrimitiveFieldType.UINT32); + } + + private void testIntegerArrayFieldVariableSize(FieldType type) { + IntegerArrayField field = IntegerArrayField.newVariable(type, "foo", -1); + field.setValue(new int[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 4, 0, 0, 0, 1, 0, 0, 0, 2, 0, 0, 0, 3, 0, 0, 0, 4, 0, 0, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testIntegerArrayFieldFixedSize() { + testIntegerArrayFieldFixedSize(PrimitiveFieldType.INT32); + testIntegerArrayFieldFixedSize(PrimitiveFieldType.UINT32); + } + + private void testIntegerArrayFieldFixedSize(FieldType type) { + IntegerArrayField field = IntegerArrayField.newVariable(type, "foo", 4); + field.setValue(new int[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 1, 0, 0, 0, 2, 0, 0, 0, 3, 0, 0, 0, 4, 0, 0, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testLongArrayFieldVariableSize() { + testLongArrayFieldVariableSize(PrimitiveFieldType.INT64); + testLongArrayFieldVariableSize(PrimitiveFieldType.UINT64); + } + + private void testLongArrayFieldVariableSize(FieldType type) { + LongArrayField field = LongArrayField.newVariable(type, "foo", -1); + field.setValue(new long[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = + new byte[] { 4, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 4, 0, 0, 0, 0, 0, 0, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testLongArrayFieldFixedSize() { + testLongArrayFieldFixedSize(PrimitiveFieldType.INT64); + testLongArrayFieldFixedSize(PrimitiveFieldType.UINT64); + } + + private void testLongArrayFieldFixedSize(FieldType type) { + LongArrayField field = LongArrayField.newVariable(type, "foo", 4); + field.setValue(new long[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = + new byte[] { 1, 0, 0, 0, 0, 0, 0, 0, 2, 0, 0, 0, 0, 0, 0, 0, 3, 0, 0, 0, 0, 0, 0, 0, 4, 0, + 0, 0, 0, 0, 0, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testShortArrayFieldVariableSize() { + testShortArrayFieldVariableSize(PrimitiveFieldType.INT16); + testShortArrayFieldVariableSize(PrimitiveFieldType.UINT16); + } + + private void testShortArrayFieldVariableSize(FieldType type) { + ShortArrayField field = ShortArrayField.newVariable(type, "foo", -1); + field.setValue(new short[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 4, 0, 0, 0, 1, 0, 2, 0, 3, 0, 4, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } + + @Test + public void testShortArrayFieldFixedSize() { + testShortArrayFieldFixedSize(PrimitiveFieldType.INT16); + testShortArrayFieldFixedSize(PrimitiveFieldType.UINT16); + } + + private void testShortArrayFieldFixedSize(FieldType type) { + ShortArrayField field = ShortArrayField.newVariable(type, "foo", 4); + field.setValue(new short[] { 1, 2, 3, 4 }); + assertEquals(type, field.getType()); + ChannelBuffer buffer = MessageBuffers.dynamicBuffer(); + field.serialize(buffer); + byte[] expected = new byte[] { 1, 0, 2, 0, 3, 0, 4, 0 }; + byte[] actual = new byte[buffer.readableBytes()]; + buffer.readBytes(actual); + assertArrayEquals(expected, actual); + } +} diff --git a/message_generation_tests/src/test/java/org/ros/message/DurationTest.java b/message_generation_tests/src/test/java/org/ros/message/DurationTest.java new file mode 100644 index 0000000000000000000000000000000000000000..fb337eb43c7dc0998f3d830eadc28314e6c85440 --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/message/DurationTest.java @@ -0,0 +1,97 @@ +/* + * 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.message; + +import static org.junit.Assert.assertEquals; +import static org.junit.Assert.assertFalse; +import static org.junit.Assert.assertTrue; + +import org.junit.Before; +import org.junit.Test; + +/** + * @author kwc@willowgarage.com (Ken Conley) + */ +public class DurationTest { + + @Before + public void setUp() { + } + + @Test + public void testConstructor() { + // Test no args constructor. + Duration t = new Duration(); + assertEquals(0, t.nsecs); + assertEquals(0, t.secs); + + // Test secs/nsecs constructor with no normalization. + t = new Duration(1, 2); + assertEquals(1, t.secs); + assertEquals(2, t.nsecs); + + // Test secs/nsecs constructor with normalization. + t = new Duration(2, -1); + assertEquals(1, t.secs); + assertEquals(1000000000 - 1, t.nsecs); + + t = new Duration(2, 1000000000 + 2); + assertEquals(3, t.secs); + assertEquals(2, t.nsecs); + } + + @Test + public void testNormalize() { + Duration d = new Duration(0, 0); + d.secs = 1; + d.nsecs = 1000000000; + d.normalize(); + assertEquals(2, d.secs); + assertEquals(0, d.nsecs); + + d.secs = 1; + d.nsecs = -1; + d.normalize(); + assertEquals(0, d.secs); + assertEquals(1000000000-1, d.nsecs); + } + + @Test + public void testIsZero() { + assertTrue(new Duration(0, 0).isZero()); + assertFalse(new Duration(1, 0).isZero()); + assertFalse(new Duration(0, 1).isZero()); + } + + @Test + public void testComparable() { + assertEquals(0, new Duration(0, 0).compareTo(new Duration(0, 0))); + assertEquals(0, new Duration(1, 0).compareTo(new Duration(1, 0))); + + assertTrue(new Duration(0, 0).compareTo(new Duration(0, -1)) > 0); + assertTrue(new Duration(0, -1).compareTo(new Duration(0, 0)) < 0); + + assertTrue(new Duration(0, 0).compareTo(new Duration(-1, 0)) > 0); + assertTrue(new Duration(-1, 0).compareTo(new Duration(0, 0)) < 0); + + assertTrue(new Duration(1, 0).compareTo(new Duration(0, 0)) > 0); + assertTrue(new Duration(0, 0).compareTo(new Duration(1, 0)) < 0); + + assertTrue(new Duration(0, 1).compareTo(new Duration(0, 0)) > 0); + assertTrue(new Duration(0, 0).compareTo(new Duration(0, 1)) < 0); + } +} \ No newline at end of file diff --git a/message_generation_tests/src/test/java/org/ros/message/TimeTest.java b/message_generation_tests/src/test/java/org/ros/message/TimeTest.java new file mode 100644 index 0000000000000000000000000000000000000000..5ef0c4d5c631a23571a2b9261866e1f7d46bc6e3 --- /dev/null +++ b/message_generation_tests/src/test/java/org/ros/message/TimeTest.java @@ -0,0 +1,102 @@ +/* + * 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.message; + +import static org.junit.Assert.assertEquals; +import static org.junit.Assert.assertFalse; +import static org.junit.Assert.assertTrue; + +import org.junit.Before; +import org.junit.Test; + +/** + * @author kwc@willowgarage.com (Ken Conley) + */ +public class TimeTest { + + @Before + public void setUp() { + } + + @Test + public void testConstructor() { + // Test no args constructor. + Time t = new Time(); + assertEquals(0, t.nsecs); + assertEquals(0, t.secs); + + // Test secs/nsecs constructor with no normalization. + t = new Time(1, 2); + assertEquals(1, t.secs); + assertEquals(2, t.nsecs); + + // Test secs/nsecs constructor with normalization. + t = new Time(2, -1); + assertEquals(1, t.secs); + assertEquals(1000000000 - 1, t.nsecs); + + t = new Time(2, 1000000000 + 2); + assertEquals(3, t.secs); + assertEquals(2, t.nsecs); + } + + @Test + public void testFromMillis() { + assertEquals(new Time(0, 0), Time.fromMillis(0)); + assertEquals(new Time(0, 1000000), Time.fromMillis(1)); + assertEquals(new Time(1, 0), Time.fromMillis(1000)); + assertEquals(new Time(10, 0), Time.fromMillis(10000)); + assertEquals(new Time(1, 1000000), Time.fromMillis(1001)); + assertEquals(new Time(1, 11000000), Time.fromMillis(1011)); + } + + @Test + public void testNormalize() { + Time t = new Time(0, 0); + t.secs = 1; + t.nsecs = 1000000000; + t.normalize(); + assertEquals(2, t.secs); + assertEquals(0, t.nsecs); + + t.secs = 1; + t.nsecs = -1; + t.normalize(); + assertEquals(0, t.secs); + assertEquals(1000000000 - 1, t.nsecs); + } + + @Test + public void testIsZero() { + assertTrue(new Time(0, 0).isZero()); + assertFalse(new Time(1, 0).isZero()); + assertFalse(new Time(0, 1).isZero()); + } + + @Test + public void testComparable() { + assertEquals(0, new Time(0, 0).compareTo(new Time(0, 0))); + assertEquals(0, new Time(1, 1).compareTo(new Time(1, 1))); + assertTrue(new Time(0, 1).compareTo(new Time(0, 0)) > 0); + + assertEquals(-1, new Time(0, 0).compareTo(new Time(0, 1))); + assertTrue(new Time(0, 0).compareTo(new Time(0, 1)) < 0); + assertTrue(new Time(1, 0).compareTo(new Time(0, 0)) > 0); + assertTrue(new Time(0, 0).compareTo(new Time(1, 0)) < 0); + + } +} \ No newline at end of file diff --git a/settings.gradle b/settings.gradle index 81c74cd0203499f90bb0fe7bfc8552dfd55366a4..9377ec995a4ae57905737d91d3922cc20a28dde0 100644 --- a/settings.gradle +++ b/settings.gradle @@ -18,3 +18,6 @@ include 'apache_xmlrpc_common', 'apache_xmlrpc_client', 'apache_xmlrpc_server', 'rosjava', 'rosjava_geometry', 'rosjava_tutorial_pubsub', 'rosjava_tutorial_services', 'rosjava_tutorial_right_hand_rule', 'rosjava_benchmarks', 'rosjava_test', 'docs' + +include 'message_generation_tests' + \ No newline at end of file