19 #include <gtest/gtest.h> 21 #include <std_msgs/Bool.h> 22 #include <std_msgs/String.h> 24 #include <variant_msgs/Test.h> 37 std::vector<uint8_t> d1(1024);
41 boost::array<int, 3> a1;
42 a1[0] = 0; a1[1] = 1; a1[2] = 2;
43 std::vector<int> a2(3);
44 a2[0] = 0; a2[1] = 1; a2[2] = 2;
54 EXPECT_EQ(a1[0], v1.
getValue<
int[3]>()[0]);
55 EXPECT_EQ(a1[1], v1.
getValue<
int[3]>()[1]);
56 EXPECT_EQ(a1[2], v1.
getValue<
int[3]>()[2]);
59 EXPECT_EQ(a2[0], v2.
getValue<
int[]>()[0]);
60 EXPECT_EQ(a2[1], v2.
getValue<
int[]>()[1]);
61 EXPECT_EQ(a2[2], v2.
getValue<
int[]>()[2]);
69 std::vector<uint8_t> d1(1024);
82 EXPECT_EQ(d1.size()-
sizeof(b1), o1.getLength());
87 EXPECT_EQ(b2, v2.
getValue<
double>());
94 std::vector<uint8_t> d1(1024);
103 variant_msgs::Test m3;
106 m3.builtin_string =
"Test";
107 m3.string.data =
"Test";
108 m3.builtin_int_array[0] = 0;
109 m3.builtin_int_array[1] = 1;
110 m3.builtin_int_array[2] = 2;
111 m3.builtin_int_vector.resize(3);
112 m3.builtin_int_vector[0] = 0;
113 m3.builtin_int_vector[1] = 1;
114 m3.builtin_int_vector[2] = 2;
126 EXPECT_EQ(m1.data, v1.
getValue<std_msgs::Bool>().data);
129 EXPECT_EQ(m2.data, v2.
getValue<std_msgs::String>().data);
132 EXPECT_EQ(m3.header.stamp, v3.
getValue<variant_msgs::Test>().header.stamp);
133 EXPECT_EQ(m3.builtin_int, v3.
getValue<variant_msgs::Test>().builtin_int);
134 EXPECT_EQ(m3.builtin_string,
135 v3.
getValue<variant_msgs::Test>().builtin_string);
136 EXPECT_EQ(m3.string.data, v3.
getValue<variant_msgs::Test>().string.data);
137 EXPECT_EQ(m3.builtin_int_array[0],
138 v3.
getValue<variant_msgs::Test>().builtin_int_array[0]);
139 EXPECT_EQ(m3.builtin_int_array[1],
140 v3.
getValue<variant_msgs::Test>().builtin_int_array[1]);
141 EXPECT_EQ(m3.builtin_int_array[2],
142 v3.
getValue<variant_msgs::Test>().builtin_int_array[2]);
143 EXPECT_EQ(m3.builtin_int_vector[0],
144 v3.
getValue<variant_msgs::Test>().builtin_int_vector[0]);
145 EXPECT_EQ(m3.builtin_int_vector[1],
146 v3.
getValue<variant_msgs::Test>().builtin_int_vector[1]);
147 EXPECT_EQ(m3.builtin_int_vector[2],
148 v3.
getValue<variant_msgs::Test>().builtin_int_vector[2]);
156 std::vector<uint8_t> d1(1024);
159 std::vector<uint8_t> d2(1024);
163 boost::array<int, 3> a1;
164 a1[0] = 0; a1[1] = 1; a1[2] = 2;
165 std::vector<int> a2(3);
166 a2[0] = 0; a2[1] = 1; a2[2] = 2;
169 v1[0] = a1[0]; v1[1] = a1[1]; v1[2] = a1[2];
172 v3 += a2[0]; v3 += a2[1]; v3 += a2[2];
184 EXPECT_EQ(a1[0], v2[0].getValue<int>());
185 EXPECT_EQ(a1[1], v2[1].getValue<int>());
186 EXPECT_EQ(a1[2], v2[2].getValue<int>());
189 EXPECT_EQ(v1[0].getValue<int>(), a1[0]);
190 EXPECT_EQ(v1[1].getValue<int>(), a1[1]);
191 EXPECT_EQ(v1[2].getValue<int>(), a1[2]);
199 EXPECT_EQ(a2[0], v4[0].getValue<int>());
200 EXPECT_EQ(a2[1], v4[1].getValue<int>());
201 EXPECT_EQ(a2[2], v4[2].getValue<int>());
205 EXPECT_EQ(v3[0].getValue<int>(), a2[0]);
206 EXPECT_EQ(v3[1].getValue<int>(), a2[1]);
207 EXPECT_EQ(v3[2].getValue<int>(), a2[2]);
215 std::vector<uint8_t> d1(1024);
218 std::vector<uint8_t> d2(1024);
223 variant_msgs::Test m1;
226 m1.builtin_string =
"Test";
227 m1.string.data =
"Test";
228 m1.builtin_int_array[0] = 0;
229 m1.builtin_int_array[1] = 1;
230 m1.builtin_int_array[2] = 2;
231 m1.builtin_int_vector.resize(3);
232 m1.builtin_int_vector[0] = 0;
233 m1.builtin_int_vector[1] = 1;
234 m1.builtin_int_vector[2] = 2;
237 getMessageDataType();
239 v1[
"header/stamp"] = m1.header.stamp;
240 v1[
"builtin_int"] = m1.builtin_int;
241 v1[
"builtin_string"] = m1.builtin_string;
242 v1[
"string/data"] = m1.string.data;
243 v1[
"builtin_int_array/0"] = m1.builtin_int_array[0];
244 v1[
"builtin_int_array/1"] = m1.builtin_int_array[1];
245 v1[
"builtin_int_array/2"] = m1.builtin_int_array[2];
247 v1[
"builtin_int_vector/0"] = m1.builtin_int_vector[0];
248 v1[
"builtin_int_vector/1"] = m1.builtin_int_vector[1];
249 v1[
"builtin_int_vector/2"] = m1.builtin_int_vector[2];
261 EXPECT_EQ(m1.builtin_int, v2[
"builtin_int"].
getValue<
int>());
262 EXPECT_EQ(m1.builtin_string, v2[
"builtin_string"].
getValue<std::string>());
263 EXPECT_EQ(m1.string.data, v2[
"string/data"].
getValue<std::string>());
264 EXPECT_EQ(m1.builtin_int_array[0], v2[
"builtin_int_array/0"].
266 EXPECT_EQ(m1.builtin_int_array[1], v2[
"builtin_int_array/1"].
268 EXPECT_EQ(m1.builtin_int_array[2], v2[
"builtin_int_array/2"].
270 EXPECT_EQ(m1.builtin_int_vector.size(), v2[
"builtin_int_vector"].
272 EXPECT_EQ(m1.builtin_int_vector[0], v2[
"builtin_int_vector/0"].
274 EXPECT_EQ(m1.builtin_int_vector[1], v2[
"builtin_int_vector/1"].
276 EXPECT_EQ(m1.builtin_int_vector[2], v2[
"builtin_int_vector/2"].
280 EXPECT_EQ(v1[
"header/stamp"].getValue<ros::Time>(), m1.header.stamp);
281 EXPECT_EQ(v1[
"builtin_int"].getValue<int>(), m1.builtin_int);
282 EXPECT_EQ(v1[
"builtin_string"].getValue<std::string>(), m1.builtin_string);
283 EXPECT_EQ(v1[
"string/data"].getValue<std::string>(), m1.string.data);
284 EXPECT_EQ(v1[
"builtin_int_array/0"].getValue<int>(),
285 m1.builtin_int_array[0]);
286 EXPECT_EQ(v1[
"builtin_int_array/1"].getValue<int>(),
287 m1.builtin_int_array[1]);
288 EXPECT_EQ(v1[
"builtin_int_array/2"].getValue<int>(),
289 m1.builtin_int_array[2]);
290 EXPECT_EQ(v1[
"builtin_int_vector"].asArray().getNumMembers(),
291 m1.builtin_int_vector.size());
292 EXPECT_EQ(v1[
"builtin_int_vector/0"].getValue<int>(),
293 m1.builtin_int_vector[0]);
294 EXPECT_EQ(v1[
"builtin_int_vector/1"].getValue<int>(),
295 m1.builtin_int_vector[1]);
296 EXPECT_EQ(v1[
"builtin_int_vector/2"].getValue<int>(),
297 m1.builtin_int_vector[2]);
Header file providing the ArraySerializer class interface.
Header file providing the MessageDefinition class interface.
Header file providing the MessageSerializer class interface.
void serialize(Stream &stream, const T &t)
Header file providing the DataTypeRegistry class interface.
uint32_t serializationLength(const T &t)
Header file providing the BuiltinSerializer class interface.
void deserialize(Stream &stream, T &t)