VariantTest.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  * Copyright (C) 2014 by Ralf Kaestner                                        *
00003  * ralf.kaestner@gmail.com                                                    *
00004  *                                                                            *
00005  * This program is free software; you can redistribute it and/or modify       *
00006  * it under the terms of the Lesser GNU General Public License as published by*
00007  * the Free Software Foundation; either version 3 of the License, or          *
00008  * (at your option) any later version.                                        *
00009  *                                                                            *
00010  * This program is distributed in the hope that it will be useful,            *
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of             *
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the               *
00013  * Lesser GNU General Public License for more details.                        *
00014  *                                                                            *
00015  * You should have received a copy of the Lesser GNU General Public License   *
00016  * along with this program. If not, see <http://www.gnu.org/licenses/>.       *
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/ArrayVariant.h>
00027 #include <variant_topic_tools/BuiltinVariant.h>
00028 #include <variant_topic_tools/DataTypeRegistry.h>
00029 #include <variant_topic_tools/MessageDefinition.h>
00030 #include <variant_topic_tools/MessageVariant.h>
00031 
00032 using namespace variant_topic_tools;
00033 
00034 TEST(Variant, Builtin) {
00035   BuiltinVariant v1 = DataType("float64").createVariant();
00036   BuiltinVariant v2 = DataType("bool").createVariant();
00037   BuiltinVariant v3 = DataType("duration").createVariant();
00038   BuiltinVariant v4 = DataType("time").createVariant();
00039   
00040   EXPECT_TRUE(v1.hasType());
00041   EXPECT_FALSE(v1.isEmpty());
00042   EXPECT_EQ(typeid(double), v1.getValueTypeInfo());
00043   EXPECT_EQ(0.0, v1.getValue<double>());
00044   EXPECT_FALSE(v1.isEmpty());
00045   EXPECT_ANY_THROW(v1.getValue<int>());
00046   EXPECT_ANY_THROW(v1.setValue(0));
00047   
00048   v1 = M_PI;
00049 
00050   EXPECT_EQ(M_PI, v1.getValue<double>());
00051   EXPECT_TRUE(v1 == M_PI);
00052   EXPECT_FALSE(v1 != M_PI);
00053   EXPECT_TRUE(v1 != 1.0);
00054   EXPECT_FALSE(v1 == 1.0);
00055   
00056   v1 = 1.0;
00057   
00058   EXPECT_TRUE(v1 != 1);
00059   EXPECT_FALSE(v1 == 1);
00060   EXPECT_EQ(1.0, v1.getNumericValue());
00061   
00062   v1.clear();
00063   
00064   EXPECT_FALSE(v1.hasType());
00065   EXPECT_TRUE(v1.isEmpty());
00066   
00067   EXPECT_EQ(typeid(uint8_t), v2.getValueTypeInfo());
00068   EXPECT_EQ(0.0, v2.getNumericValue());
00069   
00070   EXPECT_EQ(0.0, v3.getNumericValue());
00071   
00072   EXPECT_EQ(0.0, v4.getNumericValue());
00073 }
00074 
00075 TEST(Variant, Array) {
00076   DataTypeRegistry registry;
00077   
00078   ArrayVariant v1 = DataType("int32[3]").createVariant();
00079   ArrayVariant v2 = DataType("float64[]").createVariant();
00080   
00081   EXPECT_TRUE(v1.hasType());
00082   EXPECT_FALSE(v1.isEmpty());
00083   EXPECT_EQ(3, v1.getNumMembers());
00084   EXPECT_NO_THROW(v1[0] = 0);
00085   EXPECT_NO_THROW(v1[1] = 0);
00086   EXPECT_NO_THROW(v1[2] = 0);
00087   EXPECT_NO_THROW(v1.resize(3));
00088   EXPECT_ANY_THROW(v1.resize(4));
00089   EXPECT_TRUE(v1[0].hasType());
00090   EXPECT_FALSE(v1[0].isEmpty());
00091   EXPECT_NO_THROW(v1[0] = 0);
00092   EXPECT_NO_THROW(v1[1] = 1);
00093   EXPECT_NO_THROW(v1[2] = 2);
00094   EXPECT_ANY_THROW(v1[3] = 3);
00095   EXPECT_EQ(0, v1[0].getValue<int>());
00096   EXPECT_EQ(1, v1[1].getValue<int>());
00097   EXPECT_EQ(2, v1[2].getValue<int>());
00098   EXPECT_ANY_THROW(v1.clear());
00099   
00100   EXPECT_TRUE(v2.hasType());
00101   EXPECT_TRUE(v2.isEmpty());
00102   EXPECT_EQ(0, v2.getNumMembers());
00103   EXPECT_NO_THROW(v2.resize(3));
00104   EXPECT_FALSE(v2.isEmpty());
00105   EXPECT_EQ(3, v2.getNumMembers());  
00106   EXPECT_TRUE(v2[0].hasType());
00107   EXPECT_FALSE(v2[0].isEmpty());
00108   EXPECT_NO_THROW(v2[0] = 0.0);
00109   EXPECT_NO_THROW(v2[1] = 1.0);
00110   EXPECT_NO_THROW(v2[2] = 2.0);
00111   EXPECT_ANY_THROW(v2[3] = 3);
00112   EXPECT_EQ(0.0, v2[0].getValue<double>());
00113   EXPECT_EQ(1.0, v2[1].getValue<double>());
00114   EXPECT_EQ(2.0, v2[2].getValue<double>());
00115   EXPECT_NO_THROW(v2.clear());
00116   EXPECT_TRUE(v2.isEmpty());
00117   
00118   registry.clear();
00119 }
00120 
00121 TEST(Variant, Message) {
00122   DataTypeRegistry registry;
00123   
00124   MessageVariant v1(MessageDefinition::create<std_msgs::Bool>().
00125     getMessageDataType().createVariant());
00126   MessageVariant v2(MessageDefinition::create<std_msgs::String>().
00127     getMessageDataType().createVariant());
00128   MessageVariant v3(MessageDefinition::create<variant_msgs::Test>().
00129     getMessageDataType().createVariant());
00130   MessageVariant v4(registry.getDataType<variant_msgs::Test>().
00131     createVariant());
00132   
00133   EXPECT_TRUE(v1.hasType());
00134   EXPECT_FALSE(v1.isEmpty());
00135   EXPECT_EQ(typeid(void), v1.getValueTypeInfo());
00136   EXPECT_EQ(1, v1.getNumMembers());
00137   EXPECT_TRUE(v1["data"].hasType());
00138   EXPECT_FALSE(v1["data"].isEmpty());
00139   EXPECT_NO_THROW(v1["data"] = true);
00140   EXPECT_EQ(true, v1["data"].getValue<bool>());
00141   
00142   EXPECT_TRUE(v2.hasType());
00143   EXPECT_FALSE(v2.isEmpty());
00144   EXPECT_EQ(typeid(void), v2.getValueTypeInfo());
00145   EXPECT_EQ(1, v2.getNumMembers());
00146   EXPECT_TRUE(v2["data"].hasType());
00147   EXPECT_FALSE(v2["data"].isEmpty());
00148   EXPECT_NO_THROW(v2["data"] = "Test");
00149   EXPECT_EQ("Test", v2["data"].getValue<std::string>());
00150   
00151   EXPECT_TRUE(v3.hasType());
00152   EXPECT_FALSE(v3.isEmpty());
00153   EXPECT_EQ(typeid(void), v3.getValueTypeInfo());
00154   EXPECT_TRUE(v3["header"].hasType());
00155   EXPECT_FALSE(v3["header"].isEmpty());
00156   EXPECT_EQ(typeid(void), v3["header"].getValueTypeInfo());
00157   EXPECT_NO_THROW(v3["builtin_string"] = "Test");
00158   EXPECT_EQ("Test", v3["builtin_string"].getValue<std::string>());
00159   
00160   EXPECT_TRUE(v4.hasType());
00161   EXPECT_FALSE(v4.isEmpty());
00162   EXPECT_EQ(typeid(variant_msgs::Test), v4.getValueTypeInfo());
00163   EXPECT_TRUE(v4["header"].hasType());
00164   EXPECT_FALSE(v4["header"].isEmpty());
00165   EXPECT_EQ(typeid(std_msgs::Header), v4["header"].getValueTypeInfo());
00166   EXPECT_NO_THROW(v4["builtin_string"] = "Test");
00167   EXPECT_EQ("Test", v4["builtin_string"].getValue<std::string>());
00168   EXPECT_EQ(typeid(bool[3]),
00169     v4["builtin_boolean_array"].getType().getTypeInfo());
00170   EXPECT_EQ(typeid(boost::array<uint8_t, 3>),
00171     v4["builtin_boolean_array"].getValueTypeInfo());
00172   
00173   registry.clear();
00174 }


variant_topic_test
Author(s): Ralf Kaestner
autogenerated on Fri Aug 5 2016 06:06:49