19 #include <gtest/gtest.h> 21 #include <variant_msgs/Test.h> 34 ros::message_traits::definition<variant_msgs::Test>());
38 EXPECT_TRUE(t1.isValid());
39 EXPECT_TRUE(t1[0].isConstant());
40 EXPECT_EQ(
"header", t1[1].
getName());
41 EXPECT_TRUE(t1[2].isVariable());
42 EXPECT_TRUE(t1[2].getType().isBuiltin());
43 EXPECT_TRUE(t1[4].getType().isMessage());
45 EXPECT_NO_THROW(d1.
getField(
"header"));
46 EXPECT_NO_THROW(d1.
getField(
"string/data"));
47 EXPECT_ANY_THROW(d1.
getField(
"string/length"));
48 EXPECT_TRUE(d1.
hasField(
"byte_constant"));
49 EXPECT_EQ(
"std_msgs/Header", d1[
"header"].getValue().getIdentifier());
58 EXPECT_NO_THROW(d1.
load(
"variant_msgs/Test"));
59 EXPECT_NO_THROW(d1.
getField(
"header"));
60 EXPECT_NO_THROW(d1.
getField(
"string/data"));
61 EXPECT_ANY_THROW(d1.
getField(
"string/length"));
62 EXPECT_TRUE(d1.
hasField(
"byte_constant"));
63 EXPECT_EQ(
"std_msgs/Header", d1[
"header"].getValue().getIdentifier());
Header file providing the MessageDefinition class interface.
std::string getName(void *handle)
Header file providing the DataTypeRegistry class interface.
TEST(MessageDefinition, Parse)