3 #include <geometry_msgs/Point.h>
4 #include <geometry_msgs/TwistWithCovarianceStamped.h>
5 #include <geometry_msgs/Vector3.h>
7 #include <gtest/gtest.h>
14 if (str.at(str.size() - 1) !=
'\n')
23 message_traits::definition<geometry_msgs::Vector3>());
27 message_traits::definition<geometry_msgs::Point>());
31 message_traits::definition<geometry_msgs::TwistWithCovarianceStamped>());
34 EXPECT_EQ(
getFullDef(
"nonexistent/message"),
"");
41 message_traits::md5sum<geometry_msgs::Vector3>());
45 message_traits::md5sum<geometry_msgs::Point>());
48 getMD5Sum(
"geometry_msgs/TwistWithCovarianceStamped"),
49 message_traits::md5sum<geometry_msgs::TwistWithCovarianceStamped>());
52 EXPECT_EQ(
getMD5Sum(
"nonexistent/message"),
"");
59 message_traits::hasHeader<geometry_msgs::Vector3>());
63 message_traits::hasHeader<geometry_msgs::Point>());
66 hasHeader(
"geometry_msgs/TwistWithCovarianceStamped"),
67 message_traits::hasHeader<geometry_msgs::TwistWithCovarianceStamped>());
69 EXPECT_EQ(
hasHeader(
"nonexistent"),
false);
70 EXPECT_EQ(
hasHeader(
"nonexistent/message"),
false);
75 std::vector<std::string> fields;
78 ASSERT_EQ(fields.size(), 3);
79 EXPECT_EQ(
"x", fields[0]);
80 EXPECT_EQ(
"y", fields[1]);
81 EXPECT_EQ(
"z", fields[2]);
84 ASSERT_EQ(fields.size(), 3);
85 EXPECT_EQ(
"x", fields[0]);
86 EXPECT_EQ(
"y", fields[1]);
87 EXPECT_EQ(
"z", fields[2]);
89 fields =
getFieldNames(
"geometry_msgs/TwistWithCovarianceStamped");
90 ASSERT_EQ(fields.size(), 2);
91 EXPECT_EQ(
"header", fields[0]);
92 EXPECT_EQ(
"twist", fields[1]);
100 std::vector<std::string> fields;
103 ASSERT_EQ(fields.size(), 3);
104 EXPECT_EQ(
"float64", fields[0]);
105 EXPECT_EQ(
"float64", fields[1]);
106 EXPECT_EQ(
"float64", fields[2]);
109 ASSERT_EQ(fields.size(), 3);
110 EXPECT_EQ(
"float64", fields[0]);
111 EXPECT_EQ(
"float64", fields[1]);
112 EXPECT_EQ(
"float64", fields[2]);
114 fields =
getFieldTypes(
"geometry_msgs/TwistWithCovarianceStamped");
115 ASSERT_EQ(fields.size(), 2);
116 EXPECT_EQ(
"std_msgs/Header", fields[0]);
117 EXPECT_EQ(
"geometry_msgs/TwistWithCovariance", fields[1]);
125 EXPECT_NE(
getMsgFile(
"geometry_msgs/Vector3").size(), 0);
126 EXPECT_NE(
getMsgFile(
"geometry_msgs/Point").size(), 0);
127 EXPECT_NE(
getMsgFile(
"geometry_msgs/TwistWithCovariance").size(), 0);
129 EXPECT_EQ(
getMsgFile(
"nonexistent").size(), 0);
130 EXPECT_EQ(
getMsgFile(
"nonexistent/message").size(), 0);
135 EXPECT_EQ(
getMD5Text(
"geometry_msgs/Vector3"),
147 EXPECT_EQ(
getMD5Text(
"geometry_msgs/TwistWithCovarianceStamped"),
148 getMD5Sum(
"std_msgs/Header") +
" header\n" +
149 getMD5Sum(
"geometry_msgs/TwistWithCovariance") +
" twist"
152 EXPECT_EQ(
getMD5Text(
"geometry_msgs/TwistWithCovariance"),
153 getMD5Sum(
"geometry_msgs/Twist") +
" twist\n" +
154 "float64[36] covariance"
158 EXPECT_EQ(
getMD5Text(
"nonexistent/message"),
"");
161 int main(
int argc,
char **argv){
162 testing::InitGoogleTest(&argc, argv);
163 return RUN_ALL_TESTS();