MessageTest.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 
00023 #include <geometry_msgs/PoseStamped.h>
00024 
00025 #include <variant_msgs/Test.h>
00026 
00027 #include <variant_topic_tools/DataTypeRegistry.h>
00028 #include <variant_topic_tools/Message.h>
00029 #include <variant_topic_tools/MessageVariant.h>
00030 
00031 using namespace variant_topic_tools;
00032 
00033 TEST(Message, Conversion) {
00034   DataTypeRegistry registry;
00035   
00036   variant_msgs::Test m1;
00037   m1.builtin_int = 42;
00038   m1.builtin_string = "Test";
00039   Message m2 = m1;
00040   variant_msgs::Test::Ptr m3 = m2.toMessage<variant_msgs::Test>();
00041     
00042   EXPECT_EQ(ros::message_traits::datatype<variant_msgs::Test>(),
00043     m2.getType().getDataType());
00044   EXPECT_EQ(ros::message_traits::md5sum<variant_msgs::Test>(),
00045     m2.getType().getMD5Sum());
00046   EXPECT_EQ(ros::message_traits::definition<variant_msgs::Test>(),
00047     m2.getType().getDefinition());
00048   EXPECT_EQ(m1.builtin_int, m3->builtin_int);
00049   EXPECT_EQ(m1.builtin_string, m3->builtin_string);
00050   EXPECT_ANY_THROW(m2.toMessage<std_msgs::Bool>());
00051   
00052   geometry_msgs::PoseStamped m4;
00053   Message m5 = m4;
00054   EXPECT_EQ(ros::message_traits::datatype<geometry_msgs::PoseStamped>(),
00055     m5.getType().getDataType());
00056   EXPECT_EQ(ros::message_traits::md5sum<geometry_msgs::PoseStamped>(),
00057     m5.getType().getMD5Sum());
00058   EXPECT_EQ(ros::message_traits::definition<geometry_msgs::PoseStamped>(),
00059     m5.getType().getDefinition());
00060   
00061   registry.clear();
00062 }
00063 
00064 TEST(Message, Serialization) {
00065   DataTypeRegistry registry;
00066   
00067   variant_msgs::Test m1, m2;
00068   m1.builtin_int = 42;
00069   m1.builtin_string = "Test";
00070   Message m3 = m1;
00071   MessageVariant v1;
00072   
00073   EXPECT_NO_THROW(m3.deserialize(v1));
00074   EXPECT_EQ(m1.builtin_int, v1["builtin_int"].getValue<int>());
00075   EXPECT_EQ(m1.builtin_string, v1["builtin_string"].getValue<std::string>());
00076   
00077   EXPECT_NO_THROW(m3.serialize(v1));
00078   EXPECT_EQ(ros::serialization::serializationLength<variant_msgs::Test>(m1),
00079     m3.getData().size());
00080   EXPECT_NO_THROW(m2 = *m3.toMessage<variant_msgs::Test>());
00081   EXPECT_EQ(m1.builtin_int, m2.builtin_int);
00082   EXPECT_EQ(m1.builtin_string, m2.builtin_string);
00083   
00084   registry.clear();
00085 }


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