Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #include <gtest/gtest.h>
00020
00021 #include <std_msgs/Bool.h>
00022 #include <std_msgs/String.h>
00023
00024 #include <variant_msgs/Test.h>
00025
00026 #include <variant_topic_tools/ArrayDataType.h>
00027 #include <variant_topic_tools/BuiltinDataType.h>
00028 #include <variant_topic_tools/DataTypeRegistry.h>
00029 #include <variant_topic_tools/MessageDataType.h>
00030 #include <variant_topic_tools/MessageDefinition.h>
00031
00032 using namespace variant_topic_tools;
00033
00034 TEST(DataType, Array) {
00035 DataTypeRegistry registry;
00036 registry.addArrayDataType<int32_t, 3>();
00037 registry.addArrayDataType<int32_t, 0>();
00038
00039 ArrayDataType a1("int32[3]");
00040 ArrayDataType a2("int32[]");
00041
00042 EXPECT_TRUE(a1.isValid());
00043 EXPECT_TRUE(a1.isArray());
00044 EXPECT_FALSE(a1.isDynamic());
00045 EXPECT_FALSE(a1.isFixedSize());
00046
00047 EXPECT_TRUE(a2.isValid());
00048 EXPECT_TRUE(a2.isArray());
00049 EXPECT_TRUE(a2.isDynamic());
00050 EXPECT_FALSE(a2.isFixedSize());
00051
00052 EXPECT_TRUE(registry.getDataType<int32_t[3]>().isArray());
00053 EXPECT_TRUE(registry.getDataType<int32_t[]>().isArray());
00054
00055 registry.clear();
00056 }
00057
00058 TEST(DataType, Builtin) {
00059 BuiltinDataType b1("int32");
00060
00061 EXPECT_TRUE(b1.isValid());
00062 EXPECT_TRUE(b1.isBuiltin());
00063 EXPECT_TRUE(b1.hasTypeInfo());
00064 EXPECT_EQ(typeid(int32_t), b1.getTypeInfo());
00065 EXPECT_TRUE(b1.isFixedSize());
00066 EXPECT_EQ(sizeof(int32_t), b1.getSize());
00067 EXPECT_FALSE(b1.createVariant().isEmpty());
00068 EXPECT_TRUE(b1.isNumeric());
00069 }
00070
00071 TEST(DataType, Message) {
00072 DataTypeRegistry registry;
00073
00074 registry.addArrayDataType<double, 0>();
00075 registry.addArrayDataType<double, 3>();
00076
00077 MessageDataType m1 = registry.addMessageDataType<std_msgs::Bool>();
00078 MessageDataType m2 = registry.addMessageDataType("my_msgs/Double");
00079 m2.addVariableMember<double>("data");
00080 MessageDataType m3 = registry.addMessageDataType("my_msgs/Complex",
00081 "float64 real\n"
00082 "float64 imaginary\n"
00083 );
00084 MessageDataType m4 = registry.addMessageDataType("my_msgs/Vector",
00085 "float64[] data\n");
00086 MessageDataType m5 = registry.addMessageDataType("my_msgs/Array",
00087 "float64[3] data\n");
00088 MessageDataType m6 = MessageDefinition::create<variant_msgs::Test>().
00089 getMessageDataType();
00090
00091 EXPECT_TRUE(m1.isValid());
00092 EXPECT_TRUE(m1.isMessage());
00093 EXPECT_TRUE(m1.hasTypeInfo());
00094 EXPECT_FALSE(m1.hasHeader());
00095 EXPECT_EQ(typeid(std_msgs::Bool), m1.getTypeInfo());
00096 EXPECT_TRUE(m1.hasMember("data"));
00097 EXPECT_FALSE(m1.hasConstantMember("data"));
00098 EXPECT_TRUE(m1.hasVariableMember("data"));
00099 EXPECT_NO_THROW(m1.getMember("data"));
00100 EXPECT_ANY_THROW(m1.getConstantMember("data"));
00101 EXPECT_NO_THROW(m1.getVariableMember("data"));
00102 EXPECT_TRUE(m2.isValid());
00103 EXPECT_TRUE(m2.isMessage());
00104 EXPECT_FALSE(m2.hasTypeInfo());
00105 EXPECT_TRUE(m3.isValid());
00106 EXPECT_TRUE(m3.isMessage());
00107 EXPECT_FALSE(m3.hasTypeInfo());
00108 EXPECT_TRUE(m4.isValid());
00109 EXPECT_TRUE(m4.isMessage());
00110 EXPECT_FALSE(m4.hasTypeInfo());
00111 EXPECT_TRUE(m5.isValid());
00112 EXPECT_TRUE(m5.isMessage());
00113 EXPECT_FALSE(m5.hasTypeInfo());
00114 EXPECT_TRUE(m6.isValid());
00115 EXPECT_TRUE(m6.isMessage());
00116 EXPECT_FALSE(m5.hasTypeInfo());
00117 EXPECT_TRUE(m6.hasHeader());
00118 EXPECT_EQ(ros::message_traits::md5sum<variant_msgs::Test>(),
00119 m6.getMD5Sum());
00120
00121 registry.clear();
00122 }