SerializerTest.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/ArraySerializer.h>
00027 #include <variant_topic_tools/BuiltinSerializer.h>
00028 #include <variant_topic_tools/DataTypeRegistry.h>
00029 #include <variant_topic_tools/MessageDefinition.h>
00030 #include <variant_topic_tools/MessageSerializer.h>
00031 
00032 using namespace variant_topic_tools;
00033 
00034 TEST(Serializer, Array) {
00035   DataTypeRegistry registry;
00036 
00037   std::vector<uint8_t> d1(1024);
00038   ros::serialization::OStream o1(d1.data(), d1.size());
00039   ros::serialization::IStream i1(d1.data(), d1.size());
00040 
00041   boost::array<int, 3> a1;
00042   a1[0] = 0; a1[1] = 1; a1[2] = 2;
00043   std::vector<int> a2(3);
00044   a2[0] = 0; a2[1] = 1; a2[2] = 2;
00045   Variant v1, v2;
00046 
00047   Serializer s1 = registry.getDataType<int[3]>().createSerializer();
00048   Serializer s2 = registry.getDataType<int[]>().createSerializer();
00049 
00050   s1.serialize(o1, a1);
00051   EXPECT_EQ(d1.size()-ros::serialization::serializationLength(a1),
00052     o1.getLength());
00053   s1.deserialize(i1, v1);
00054   EXPECT_EQ(a1[0], v1.getValue<int[3]>()[0]);
00055   EXPECT_EQ(a1[1], v1.getValue<int[3]>()[1]);
00056   EXPECT_EQ(a1[2], v1.getValue<int[3]>()[2]);
00057   s2.serialize(o1, a2);
00058   s2.deserialize(i1, v2);
00059   EXPECT_EQ(a2[0], v2.getValue<int[]>()[0]);
00060   EXPECT_EQ(a2[1], v2.getValue<int[]>()[1]);
00061   EXPECT_EQ(a2[2], v2.getValue<int[]>()[2]);
00062 
00063   registry.clear();
00064 }
00065 
00066 TEST(Serializer, Builtin) {
00067   DataTypeRegistry registry;
00068 
00069   std::vector<uint8_t> d1(1024);
00070   ros::serialization::OStream o1(d1.data(), d1.size());
00071   ros::serialization::IStream i1(d1.data(), d1.size());
00072 
00073   int b1 = 42;
00074   double b2 = 42.0;
00075   Variant v1, v2;
00076 
00077   Serializer s1 = registry.getDataType<int>().createSerializer();
00078   Serializer s2 = registry.getDataType<double>().createSerializer();
00079   Serializer s3 = registry.getDataType<bool>().createSerializer();
00080 
00081   s1.serialize(o1, b1);
00082   EXPECT_EQ(d1.size()-sizeof(b1), o1.getLength());
00083   s1.deserialize(i1, v1);
00084   EXPECT_EQ(b1, v1.getValue<int>());
00085   s2.serialize(o1, b2);
00086   s2.deserialize(i1, v2);
00087   EXPECT_EQ(b2, v2.getValue<double>());
00088   EXPECT_ANY_THROW(s3.serialize(o1, b1));
00089 }
00090 
00091 TEST(Serializer, Message) {
00092   DataTypeRegistry registry;
00093 
00094   std::vector<uint8_t> d1(1024);
00095   ros::serialization::OStream o1(d1.data(), d1.size());
00096   ros::serialization::IStream i1(d1.data(), d1.size());
00097   ros::Time::init();
00098 
00099   std_msgs::Bool m1;
00100   m1.data = true;
00101   std_msgs::String m2;
00102   m2.data = "Test";
00103   variant_msgs::Test m3;
00104   m3.header.stamp = ros::Time::now();
00105   m3.builtin_int = 42;
00106   m3.builtin_string = "Test";
00107   m3.string.data = "Test";
00108   m3.builtin_int_array[0] = 0;
00109   m3.builtin_int_array[1] = 1;
00110   m3.builtin_int_array[2] = 2;
00111   m3.builtin_int_vector.resize(3);
00112   m3.builtin_int_vector[0] = 0;
00113   m3.builtin_int_vector[1] = 1;
00114   m3.builtin_int_vector[2] = 2;
00115   Variant v1, v2, v3;
00116 
00117   Serializer s1 = registry.getDataType<std_msgs::Bool>().createSerializer();
00118   Serializer s2 = registry.getDataType<std_msgs::String>().createSerializer();
00119   Serializer s3 = registry.getDataType<variant_msgs::Test>().
00120     createSerializer();
00121 
00122   s1.serialize(o1, m1);
00123   EXPECT_EQ(d1.size()-ros::serialization::serializationLength(m1),
00124     o1.getLength());
00125   s1.deserialize(i1, v1);
00126   EXPECT_EQ(m1.data, v1.getValue<std_msgs::Bool>().data);
00127   s2.serialize(o1, m2);
00128   s2.deserialize(i1, v2);
00129   EXPECT_EQ(m2.data, v2.getValue<std_msgs::String>().data);
00130   s3.serialize(o1, m3);
00131   s3.deserialize(i1, v3);
00132   EXPECT_EQ(m3.header.stamp, v3.getValue<variant_msgs::Test>().header.stamp);
00133   EXPECT_EQ(m3.builtin_int, v3.getValue<variant_msgs::Test>().builtin_int);
00134   EXPECT_EQ(m3.builtin_string,
00135     v3.getValue<variant_msgs::Test>().builtin_string);
00136   EXPECT_EQ(m3.string.data, v3.getValue<variant_msgs::Test>().string.data);
00137   EXPECT_EQ(m3.builtin_int_array[0],
00138     v3.getValue<variant_msgs::Test>().builtin_int_array[0]);
00139   EXPECT_EQ(m3.builtin_int_array[1],
00140     v3.getValue<variant_msgs::Test>().builtin_int_array[1]);
00141   EXPECT_EQ(m3.builtin_int_array[2],
00142     v3.getValue<variant_msgs::Test>().builtin_int_array[2]);
00143   EXPECT_EQ(m3.builtin_int_vector[0],
00144     v3.getValue<variant_msgs::Test>().builtin_int_vector[0]);
00145   EXPECT_EQ(m3.builtin_int_vector[1],
00146     v3.getValue<variant_msgs::Test>().builtin_int_vector[1]);
00147   EXPECT_EQ(m3.builtin_int_vector[2],
00148     v3.getValue<variant_msgs::Test>().builtin_int_vector[2]);
00149 
00150   registry.clear();
00151 }
00152 
00153 TEST(Serializer, VariantArray) {
00154   DataTypeRegistry registry;
00155 
00156   std::vector<uint8_t> d1(1024);
00157   ros::serialization::OStream o1(d1.data(), d1.size());
00158   ros::serialization::IStream i1(d1.data(), d1.size());
00159   std::vector<uint8_t> d2(1024);
00160   ros::serialization::OStream o2(d2.data(), d2.size());
00161   ros::serialization::IStream i2(d2.data(), d2.size());
00162 
00163   boost::array<int, 3> a1;
00164   a1[0] = 0; a1[1] = 1; a1[2] = 2;
00165   std::vector<int> a2(3);
00166   a2[0] = 0; a2[1] = 1; a2[2] = 2;
00167 
00168   ArrayVariant v1 = registry.getDataType("int32[3]").createVariant();
00169   v1[0] = a1[0]; v1[1] = a1[1]; v1[2] = a1[2];
00170   ArrayVariant v2 = registry.getDataType("int32[3]").createVariant();
00171   ArrayVariant v3 = registry.getDataType("int32[]").createVariant();
00172   v3 += a2[0]; v3 += a2[1]; v3 += a2[2];
00173   ArrayVariant v4 = registry.getDataType("int32[]").createVariant();
00174 
00175   Serializer s1 = v1.createSerializer();
00176   Serializer s2 = v3.createSerializer();
00177 
00178   s1.serialize(o1, v1);
00179   EXPECT_EQ(d1.size()-v1.getType().getSize(), o1.getLength());
00180   s1.deserialize(i1, v2);
00181   EXPECT_EQ(v1, v2);
00182   ros::serialization::serialize(o2, a1);
00183   s1.deserialize(i2, v2);
00184   EXPECT_EQ(a1[0], v2[0].getValue<int>());
00185   EXPECT_EQ(a1[1], v2[1].getValue<int>());
00186   EXPECT_EQ(a1[2], v2[2].getValue<int>());
00187   s1.serialize(o2, v1);
00188   ros::serialization::deserialize(i2, a1);
00189   EXPECT_EQ(v1[0].getValue<int>(), a1[0]);
00190   EXPECT_EQ(v1[1].getValue<int>(), a1[1]);
00191   EXPECT_EQ(v1[2].getValue<int>(), a1[2]);
00192 
00193   s2.serialize(o1, v3);
00194   s2.deserialize(i1, v4);
00195   EXPECT_EQ(v3, v4);
00196   ros::serialization::serialize(o2, a2);
00197   s2.deserialize(i2, v4);
00198   EXPECT_EQ(a2.size(), v4.getNumMembers());
00199   EXPECT_EQ(a2[0], v4[0].getValue<int>());
00200   EXPECT_EQ(a2[1], v4[1].getValue<int>());
00201   EXPECT_EQ(a2[2], v4[2].getValue<int>());
00202   s2.serialize(o2, v3);
00203   ros::serialization::deserialize(i2, a2);
00204   EXPECT_EQ(v3.getNumMembers(), a2.size());
00205   EXPECT_EQ(v3[0].getValue<int>(), a2[0]);
00206   EXPECT_EQ(v3[1].getValue<int>(), a2[1]);
00207   EXPECT_EQ(v3[2].getValue<int>(), a2[2]);
00208 
00209   registry.clear();
00210 }
00211 
00212 TEST(Serializer, VariantMessage) {
00213   DataTypeRegistry registry;
00214 
00215   std::vector<uint8_t> d1(1024);
00216   ros::serialization::OStream o1(d1.data(), d1.size());
00217   ros::serialization::IStream i1(d1.data(), d1.size());
00218   std::vector<uint8_t> d2(1024);
00219   ros::serialization::OStream o2(d2.data(), d2.size());
00220   ros::serialization::IStream i2(d2.data(), d2.size());
00221   ros::Time::init();
00222 
00223   variant_msgs::Test m1;
00224   m1.header.stamp = ros::Time::now();
00225   m1.builtin_int = 42;
00226   m1.builtin_string = "Test";
00227   m1.string.data = "Test";
00228   m1.builtin_int_array[0] = 0;
00229   m1.builtin_int_array[1] = 1;
00230   m1.builtin_int_array[2] = 2;
00231   m1.builtin_int_vector.resize(3);
00232   m1.builtin_int_vector[0] = 0;
00233   m1.builtin_int_vector[1] = 1;
00234   m1.builtin_int_vector[2] = 2;
00235 
00236   MessageDataType t1 = MessageDefinition::create<variant_msgs::Test>().
00237     getMessageDataType();
00238   MessageVariant v1 = t1.createVariant();
00239   v1["header/stamp"] = m1.header.stamp;
00240   v1["builtin_int"] = m1.builtin_int;
00241   v1["builtin_string"] = m1.builtin_string;
00242   v1["string/data"] = m1.string.data;
00243   v1["builtin_int_array/0"] = m1.builtin_int_array[0];
00244   v1["builtin_int_array/1"] = m1.builtin_int_array[1];
00245   v1["builtin_int_array/2"] = m1.builtin_int_array[2];
00246   v1["builtin_int_vector"].asArray().resize(3);
00247   v1["builtin_int_vector/0"] = m1.builtin_int_vector[0];
00248   v1["builtin_int_vector/1"] = m1.builtin_int_vector[1];
00249   v1["builtin_int_vector/2"] = m1.builtin_int_vector[2];
00250   MessageVariant v2 = t1.createVariant();
00251 
00252   Serializer s1 = v1.createSerializer();
00253 
00254   s1.serialize(o1, v1);
00255   s1.deserialize(i1, v2);
00256   EXPECT_EQ(v1, v2);
00257 
00258   ros::serialization::serialize(o2, m1);
00259   s1.deserialize(i2, v2);
00260   EXPECT_EQ(m1.header.stamp, v2["header/stamp"].getValue<ros::Time>());
00261   EXPECT_EQ(m1.builtin_int, v2["builtin_int"].getValue<int>());
00262   EXPECT_EQ(m1.builtin_string, v2["builtin_string"].getValue<std::string>());
00263   EXPECT_EQ(m1.string.data, v2["string/data"].getValue<std::string>());
00264   EXPECT_EQ(m1.builtin_int_array[0], v2["builtin_int_array/0"].
00265     getValue<int>());
00266   EXPECT_EQ(m1.builtin_int_array[1], v2["builtin_int_array/1"].
00267     getValue<int>());
00268   EXPECT_EQ(m1.builtin_int_array[2], v2["builtin_int_array/2"].
00269     getValue<int>());
00270   EXPECT_EQ(m1.builtin_int_vector.size(), v2["builtin_int_vector"].
00271     asArray().getNumMembers());
00272   EXPECT_EQ(m1.builtin_int_vector[0], v2["builtin_int_vector/0"].
00273     getValue<int>());
00274   EXPECT_EQ(m1.builtin_int_vector[1], v2["builtin_int_vector/1"].
00275     getValue<int>());
00276   EXPECT_EQ(m1.builtin_int_vector[2], v2["builtin_int_vector/2"].
00277     getValue<int>());
00278   s1.serialize(o2, v1);
00279   ros::serialization::deserialize(i2, m1);
00280   EXPECT_EQ(v1["header/stamp"].getValue<ros::Time>(), m1.header.stamp);
00281   EXPECT_EQ(v1["builtin_int"].getValue<int>(), m1.builtin_int);
00282   EXPECT_EQ(v1["builtin_string"].getValue<std::string>(), m1.builtin_string);
00283   EXPECT_EQ(v1["string/data"].getValue<std::string>(), m1.string.data);
00284   EXPECT_EQ(v1["builtin_int_array/0"].getValue<int>(),
00285     m1.builtin_int_array[0]);
00286   EXPECT_EQ(v1["builtin_int_array/1"].getValue<int>(),
00287     m1.builtin_int_array[1]);
00288   EXPECT_EQ(v1["builtin_int_array/2"].getValue<int>(),
00289     m1.builtin_int_array[2]);
00290   EXPECT_EQ(v1["builtin_int_vector"].asArray().getNumMembers(),
00291     m1.builtin_int_vector.size());
00292   EXPECT_EQ(v1["builtin_int_vector/0"].getValue<int>(),
00293     m1.builtin_int_vector[0]);
00294   EXPECT_EQ(v1["builtin_int_vector/1"].getValue<int>(),
00295     m1.builtin_int_vector[1]);
00296   EXPECT_EQ(v1["builtin_int_vector/2"].getValue<int>(),
00297     m1.builtin_int_vector[2]);
00298 
00299   registry.clear();
00300 }


variant_topic_test
Author(s): Ralf Kaestner
autogenerated on Tue Jul 9 2019 03:18:49