DataTypeTest.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright (C) 2014 by Ralf Kaestner *
3  * ralf.kaestner@gmail.com *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the Lesser GNU General Public License as published by*
7  * the Free Software Foundation; either version 3 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * Lesser GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the Lesser GNU General Public License *
16  * along with this program. If not, see <http://www.gnu.org/licenses/>. *
17  ******************************************************************************/
18 
19 #include <gtest/gtest.h>
20 
21 #include <std_msgs/Bool.h>
22 #include <std_msgs/String.h>
23 
24 #include <variant_msgs/Test.h>
25 
31 
32 using namespace variant_topic_tools;
33 
34 TEST(DataType, Array) {
35  DataTypeRegistry registry;
36  registry.addArrayDataType<int32_t, 3>();
37  registry.addArrayDataType<int32_t, 0>();
38 
39  ArrayDataType a1("int32[3]");
40  ArrayDataType a2("int32[]");
41 
42  EXPECT_TRUE(a1.isValid());
43  EXPECT_TRUE(a1.isArray());
44  EXPECT_FALSE(a1.isDynamic());
45  EXPECT_FALSE(a1.isFixedSize());
46 
47  EXPECT_TRUE(a2.isValid());
48  EXPECT_TRUE(a2.isArray());
49  EXPECT_TRUE(a2.isDynamic());
50  EXPECT_FALSE(a2.isFixedSize());
51 
52  EXPECT_TRUE(registry.getDataType<int32_t[3]>().isArray());
53  EXPECT_TRUE(registry.getDataType<int32_t[]>().isArray());
54 
55  registry.clear();
56 }
57 
58 TEST(DataType, Builtin) {
59  BuiltinDataType b1("int32");
60 
61  EXPECT_TRUE(b1.isValid());
62  EXPECT_TRUE(b1.isBuiltin());
63  EXPECT_TRUE(b1.hasTypeInfo());
64  EXPECT_EQ(typeid(int32_t), b1.getTypeInfo());
65  EXPECT_TRUE(b1.isFixedSize());
66  EXPECT_EQ(sizeof(int32_t), b1.getSize());
67  EXPECT_FALSE(b1.createVariant().isEmpty());
68  EXPECT_TRUE(b1.isNumeric());
69 }
70 
72  DataTypeRegistry registry;
73 
74  registry.addArrayDataType<double, 0>();
75  registry.addArrayDataType<double, 3>();
76 
77  MessageDataType m1 = registry.addMessageDataType<std_msgs::Bool>();
78  MessageDataType m2 = registry.addMessageDataType("my_msgs/Double");
79  m2.addVariableMember<double>("data");
80  MessageDataType m3 = registry.addMessageDataType("my_msgs/Complex",
81  "float64 real\n"
82  "float64 imaginary\n"
83  );
84  MessageDataType m4 = registry.addMessageDataType("my_msgs/Vector",
85  "float64[] data\n");
86  MessageDataType m5 = registry.addMessageDataType("my_msgs/Array",
87  "float64[3] data\n");
88  MessageDataType m6 = MessageDefinition::create<variant_msgs::Test>().
89  getMessageDataType();
90 
91  EXPECT_TRUE(m1.isValid());
92  EXPECT_TRUE(m1.isMessage());
93  EXPECT_TRUE(m1.hasTypeInfo());
94  EXPECT_FALSE(m1.hasHeader());
95  EXPECT_EQ(typeid(std_msgs::Bool), m1.getTypeInfo());
96  EXPECT_TRUE(m1.hasMember("data"));
97  EXPECT_FALSE(m1.hasConstantMember("data"));
98  EXPECT_TRUE(m1.hasVariableMember("data"));
99  EXPECT_NO_THROW(m1.getMember("data"));
100  EXPECT_ANY_THROW(m1.getConstantMember("data"));
101  EXPECT_NO_THROW(m1.getVariableMember("data"));
102  EXPECT_TRUE(m2.isValid());
103  EXPECT_TRUE(m2.isMessage());
104  EXPECT_FALSE(m2.hasTypeInfo());
105  EXPECT_TRUE(m3.isValid());
106  EXPECT_TRUE(m3.isMessage());
107  EXPECT_FALSE(m3.hasTypeInfo());
108  EXPECT_TRUE(m4.isValid());
109  EXPECT_TRUE(m4.isMessage());
110  EXPECT_FALSE(m4.hasTypeInfo());
111  EXPECT_TRUE(m5.isValid());
112  EXPECT_TRUE(m5.isMessage());
113  EXPECT_FALSE(m5.hasTypeInfo());
114  EXPECT_TRUE(m6.isValid());
115  EXPECT_TRUE(m6.isMessage());
116  EXPECT_FALSE(m5.hasTypeInfo());
117  EXPECT_TRUE(m6.hasHeader());
118  EXPECT_EQ(ros::message_traits::md5sum<variant_msgs::Test>(),
119  m6.getMD5Sum());
120 
121  registry.clear();
122 }
void addVariableMember(const MessageVariable &member)
Add a variable member to this message data type (overloaded version taking a message variable) ...
Header file providing the MessageDefinition class interface.
Generic message type.
Definition: Message.h:43
bool hasTypeInfo() const
True, if this data type has type information.
Definition: DataType.cpp:137
Header file providing the ArrayDataType class interface.
void clear()
Clear the data type registry.
bool isArray() const
True, if this data type represents an array type.
Definition: DataType.cpp:98
bool isMessage() const
True, if this data type represents a message type.
Definition: DataType.cpp:112
std::string getMD5Sum() const
Retrieve the MD5 sum of this message data type.
TEST(DataType, Array)
const std::type_info & getTypeInfo() const
Retrieve the type information associated with this data type.
Definition: DataType.cpp:84
bool isValid() const
True, if this data type is valid.
Definition: DataType.cpp:133
bool isNumeric() const
True, if this built-in data type is numeric.
Header file providing the DataTypeRegistry class interface.
Header file providing the MessageDataType class interface.
DataType getDataType(const std::string &identifier)
Retrieve a data type from the registry by identifier (non-const version)
bool isEmpty() const
True, if the variant is empty, i.e., does not have a value assigned.
Definition: Variant.cpp:95
bool isDynamic() const
True, if this array data type represents a dynamic array.
ArrayDataType addArrayDataType(const DataType &memberType, size_t numMembers=0)
Add an array data type to the data type registry (variant-typed version)
bool isFixedSize() const
True, if this data type represents a fixed-size data type, as opposed to a variable-size data type...
Definition: DataType.cpp:119
size_t getSize() const
Retrieve the size of the instances of this data type.
Definition: DataType.cpp:91
Variant createVariant() const
Create a variant from this data type.
Definition: DataType.cpp:168
bool isBuiltin() const
True, if this data type represents a built-in type.
Definition: DataType.cpp:105
MessageDataType addMessageDataType(const std::string &identifier, const MessageFieldCollection< MessageConstant > &constantMembers=MessageFieldCollection< MessageConstant >(), const MessageFieldCollection< MessageVariable > &variableMembers=MessageFieldCollection< MessageVariable >())
Add a message data type to the data type registry (variant-typed version taking an identifier...
bool hasHeader() const
True, if this message data type has a header.
Header file providing the BuiltinDataType class interface.


variant_topic_tools
Author(s): Ralf Kaestner
autogenerated on Sat Jan 9 2021 03:56:49