test.cpp
Go to the documentation of this file.
2 
3 #include <geometry_msgs/Point.h>
4 #include <geometry_msgs/TwistWithCovarianceStamped.h>
5 #include <geometry_msgs/Vector3.h>
6 
7 #include <gtest/gtest.h>
8 
9 using namespace ros;
10 using namespace ros::message;
11 
12 std::string appendNewline(const std::string& str)
13 {
14  if (str.at(str.size() - 1) != '\n')
15  return str + "\n";
16  return str;
17 }
18 
19 TEST(CppMsgDef, getFullDef)
20 {
21  EXPECT_EQ(
22  appendNewline(getFullDef("geometry_msgs/Vector3")),
23  message_traits::definition<geometry_msgs::Vector3>());
24 
25  EXPECT_EQ(
26  appendNewline(getFullDef("geometry_msgs/Point")),
27  message_traits::definition<geometry_msgs::Point>());
28 
29  EXPECT_EQ(
30  appendNewline(getFullDef("geometry_msgs/TwistWithCovarianceStamped")),
31  message_traits::definition<geometry_msgs::TwistWithCovarianceStamped>());
32 
33  EXPECT_EQ(getFullDef("nonexistent"), "");
34  EXPECT_EQ(getFullDef("nonexistent/message"), "");
35 }
36 
37 TEST(CppMsgDef, getMD5Sum)
38 {
39  EXPECT_EQ(
40  getMD5Sum("geometry_msgs/Vector3"),
41  message_traits::md5sum<geometry_msgs::Vector3>());
42 
43  EXPECT_EQ(
44  getMD5Sum("geometry_msgs/Point"),
45  message_traits::md5sum<geometry_msgs::Point>());
46 
47  EXPECT_EQ(
48  getMD5Sum("geometry_msgs/TwistWithCovarianceStamped"),
49  message_traits::md5sum<geometry_msgs::TwistWithCovarianceStamped>());
50 
51  EXPECT_EQ(getMD5Sum("nonexistent"), "");
52  EXPECT_EQ(getMD5Sum("nonexistent/message"), "");
53 }
54 
55 TEST(CppMsgDef, hasHeader)
56 {
57  EXPECT_EQ(
58  hasHeader("geometry_msgs/Vector3"),
59  message_traits::hasHeader<geometry_msgs::Vector3>());
60 
61  EXPECT_EQ(
62  hasHeader("geometry_msgs/Point"),
63  message_traits::hasHeader<geometry_msgs::Point>());
64 
65  EXPECT_EQ(
66  hasHeader("geometry_msgs/TwistWithCovarianceStamped"),
67  message_traits::hasHeader<geometry_msgs::TwistWithCovarianceStamped>());
68 
69  EXPECT_EQ(hasHeader("nonexistent"), false);
70  EXPECT_EQ(hasHeader("nonexistent/message"), false);
71 }
72 
73 TEST(CppMsgDef, getFieldNames)
74 {
75  std::vector<std::string> fields;
76 
77  fields = getFieldNames("geometry_msgs/Vector3");
78  ASSERT_EQ(fields.size(), 3);
79  EXPECT_EQ("x", fields[0]);
80  EXPECT_EQ("y", fields[1]);
81  EXPECT_EQ("z", fields[2]);
82 
83  fields = getFieldNames("geometry_msgs/Point");
84  ASSERT_EQ(fields.size(), 3);
85  EXPECT_EQ("x", fields[0]);
86  EXPECT_EQ("y", fields[1]);
87  EXPECT_EQ("z", fields[2]);
88 
89  fields = getFieldNames("geometry_msgs/TwistWithCovarianceStamped");
90  ASSERT_EQ(fields.size(), 2);
91  EXPECT_EQ("header", fields[0]);
92  EXPECT_EQ("twist", fields[1]);
93 
94  EXPECT_EQ(getFieldNames("nonexistent").size(), 0);
95  EXPECT_EQ(getFieldNames("nonexistent/message").size(), 0);
96 }
97 
98 TEST(CppMsgDef, getFieldTypes)
99 {
100  std::vector<std::string> fields;
101 
102  fields = getFieldTypes("geometry_msgs/Vector3");
103  ASSERT_EQ(fields.size(), 3);
104  EXPECT_EQ("float64", fields[0]);
105  EXPECT_EQ("float64", fields[1]);
106  EXPECT_EQ("float64", fields[2]);
107 
108  fields = getFieldTypes("geometry_msgs/Point");
109  ASSERT_EQ(fields.size(), 3);
110  EXPECT_EQ("float64", fields[0]);
111  EXPECT_EQ("float64", fields[1]);
112  EXPECT_EQ("float64", fields[2]);
113 
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]);
118 
119  EXPECT_EQ(getFieldTypes("nonexistent").size(), 0);
120  EXPECT_EQ(getFieldTypes("nonexistent/message").size(), 0);
121 }
122 
123 TEST(CppMsgDef, getMsgFile)
124 {
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);
128 
129  EXPECT_EQ(getMsgFile("nonexistent").size(), 0);
130  EXPECT_EQ(getMsgFile("nonexistent/message").size(), 0);
131 }
132 
133 TEST(CppMsgDef, getMD5Text)
134 {
135  EXPECT_EQ(getMD5Text("geometry_msgs/Vector3"),
136  "float64 x\n"
137  "float64 y\n"
138  "float64 z"
139  );
140 
141  EXPECT_EQ(getMD5Text("geometry_msgs/Point"),
142  "float64 x\n"
143  "float64 y\n"
144  "float64 z"
145  );
146 
147  EXPECT_EQ(getMD5Text("geometry_msgs/TwistWithCovarianceStamped"),
148  getMD5Sum("std_msgs/Header") + " header\n" +
149  getMD5Sum("geometry_msgs/TwistWithCovariance") + " twist"
150  );
151 
152  EXPECT_EQ(getMD5Text("geometry_msgs/TwistWithCovariance"),
153  getMD5Sum("geometry_msgs/Twist") + " twist\n" +
154  "float64[36] covariance"
155  );
156 
157  EXPECT_EQ(getMD5Text("nonexistent"), "");
158  EXPECT_EQ(getMD5Text("nonexistent/message"), "");
159 }
160 
161 int main(int argc, char **argv){
162  testing::InitGoogleTest(&argc, argv);
163  return RUN_ALL_TESTS();
164 }
appendNewline
std::string appendNewline(const std::string &str)
Definition: test.cpp:12
ros
ros::message::getMD5Text
std::string getMD5Text(const std::string &messageType)
Return the exact text from which the MD5 sum of the message is computed.
Definition: rosmsg_cpp.cpp:256
ros::message::getFieldNames
std::vector< std::string > getFieldNames(const std::string &messageType)
Return the names of fields of the message type (non-recursive).
Definition: rosmsg_cpp.cpp:172
TEST
TEST(CppMsgDef, getFullDef)
Definition: test.cpp:19
ros::message::getFieldTypes
std::vector< std::string > getFieldTypes(const std::string &messageType)
Return the types of fields of the message type (non-recursive).
Definition: rosmsg_cpp.cpp:188
ros::message
Definition: rosmsg_cpp.h:8
ros::message::getFullDef
std::string getFullDef(const std::string &messageType)
Return the full recursive definition of the message type - the same as genpy generates.
Definition: rosmsg_cpp.cpp:146
rosmsg_cpp.h
ros::message::hasHeader
bool hasHeader(const std::string &messageType)
Tell whether the given message type has a header field.
Definition: rosmsg_cpp.cpp:162
ros::message::getMsgFile
std::string getMsgFile(const std::string &messageType)
Get the path to the .msg file corresponding to the given message type.
Definition: rosmsg_cpp.cpp:204
main
int main(int argc, char **argv)
Definition: test.cpp:161
ros::message::getMD5Sum
std::string getMD5Sum(const std::string &messageType)
Return the MD5 sum of the message type - the same as genpy generates.
Definition: rosmsg_cpp.cpp:154


rosmsg_cpp
Author(s): Martin Pecka
autogenerated on Mon Apr 17 2023 02:30:24