MessageTest.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 
23 #include <geometry_msgs/PoseStamped.h>
24 
25 #include <variant_msgs/Test.h>
26 
30 
31 using namespace variant_topic_tools;
32 
33 TEST(Message, Conversion) {
34  DataTypeRegistry registry;
35 
36  variant_msgs::Test m1;
37  m1.builtin_int = 42;
38  m1.builtin_string = "Test";
39  Message m2 = m1;
40  variant_msgs::Test::Ptr m3 = m2.toMessage<variant_msgs::Test>();
41 
42  EXPECT_EQ(ros::message_traits::datatype<variant_msgs::Test>(),
43  m2.getType().getDataType());
44  EXPECT_EQ(ros::message_traits::md5sum<variant_msgs::Test>(),
45  m2.getType().getMD5Sum());
46  EXPECT_EQ(ros::message_traits::definition<variant_msgs::Test>(),
47  m2.getType().getDefinition());
48  EXPECT_EQ(m1.builtin_int, m3->builtin_int);
49  EXPECT_EQ(m1.builtin_string, m3->builtin_string);
50  EXPECT_ANY_THROW(m2.toMessage<std_msgs::Bool>());
51 
52  geometry_msgs::PoseStamped m4;
53  Message m5 = m4;
54  EXPECT_EQ(ros::message_traits::datatype<geometry_msgs::PoseStamped>(),
55  m5.getType().getDataType());
56  EXPECT_EQ(ros::message_traits::md5sum<geometry_msgs::PoseStamped>(),
57  m5.getType().getMD5Sum());
58  EXPECT_EQ(ros::message_traits::definition<geometry_msgs::PoseStamped>(),
59  m5.getType().getDefinition());
60 
61  registry.clear();
62 }
63 
64 TEST(Message, Serialization) {
65  DataTypeRegistry registry;
66 
67  variant_msgs::Test m1, m2;
68  m1.builtin_int = 42;
69  m1.builtin_string = "Test";
70  Message m3 = m1;
71  MessageVariant v1;
72 
73  EXPECT_NO_THROW(m3.deserialize(v1));
74  EXPECT_EQ(m1.builtin_int, v1["builtin_int"].getValue<int>());
75  EXPECT_EQ(m1.builtin_string, v1["builtin_string"].getValue<std::string>());
76 
77  EXPECT_NO_THROW(m3.serialize(v1));
78  EXPECT_EQ(ros::serialization::serializationLength<variant_msgs::Test>(m1),
79  m3.getData().size());
80  EXPECT_NO_THROW(m2 = *m3.toMessage<variant_msgs::Test>());
81  EXPECT_EQ(m1.builtin_int, m2.builtin_int);
82  EXPECT_EQ(m1.builtin_string, m2.builtin_string);
83 
84  registry.clear();
85 }
void serialize(const MessageVariant &variant)
Attempt to serialize this message from a variant.
Definition: Message.cpp:95
Generic message type.
Definition: Message.h:43
Header file providing the Message class interface.
Header file providing the MessageVariant class interface.
void clear()
Clear the data type registry.
const MessageType & getType() const
Retrieve the message type.
Definition: Message.cpp:67
const std::string & getDefinition() const
Retrieve the message definition.
Definition: MessageType.cpp:90
boost::shared_ptr< T > toMessage() const
Attempt to convert the message to a strong-typed message.
const std::string & getDataType() const
Retrieve the data type of the message.
Definition: MessageType.cpp:74
Header file providing the DataTypeRegistry class interface.
void deserialize(MessageVariant &variant) const
Attempt to deserialize this message into a variant.
Definition: Message.cpp:109
T & getValue(int index)
Retrieve a member value of the collection by index (non-const version)
const std::string & getMD5Sum() const
Retrieve the MD5 sum of the message.
Definition: MessageType.cpp:82
std::vector< uint8_t > & getData()
Retrieve the message data (non-const version)
Definition: Message.cpp:75
TEST(Message, Conversion)
Definition: MessageTest.cpp:33


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