parser_test.cpp
Go to the documentation of this file.
1 #include "config.h"
2 #include <gtest/gtest.h>
3 
4 #include <geometry_msgs/Pose.h>
5 #include <sensor_msgs/NavSatStatus.h>
6 #include <sensor_msgs/Imu.h>
7 #include <std_msgs/Int16MultiArray.h>
9 
10 using namespace ros::message_traits;
11 using namespace RosIntrospection;
12 
13 TEST(RosType, builtin_int32)
14 {
15  ROSField f("int32 number");
16 
17  EXPECT_EQ(f.type().baseName(), "int32");
18  EXPECT_EQ(f.type().msgName(), "int32");
19  EXPECT_EQ(f.type().pkgName().size(), 0);
20  EXPECT_EQ(f.type().isBuiltin(), true);
21  EXPECT_EQ(f.type().typeSize(), 4);
22  EXPECT_EQ(f.isArray(), false);
23  EXPECT_EQ(f.arraySize(), 1);
24  EXPECT_EQ(f.name(), "number");
25 }
26 
27 TEST(RosType, builtin_string)
28 {
29  ROSField f("string my_string");
30  EXPECT_EQ(f.type().baseName(), "string");
31  EXPECT_EQ(f.type().msgName() , "string");
32  EXPECT_EQ(f.type().pkgName().size(), 0);
33  EXPECT_EQ(f.type().isBuiltin(), true);
34  EXPECT_EQ(f.type().typeSize(), -1);
35  EXPECT_EQ(f.isArray(), false);
36  EXPECT_EQ(f.arraySize(), 1);
37  EXPECT_EQ(f.name(), "my_string");
38 }
39 
40 
41 TEST(RosType, builtin_fixedlen_array)
42 {
43  ROSField f("float64[32] my_array");
44 
45  EXPECT_EQ(f.type().baseName(), "float64");
46  EXPECT_EQ(f.type().msgName(), "float64");
47  EXPECT_EQ(f.type().pkgName().size(), 0 );
48  EXPECT_EQ(f.type().isBuiltin(), true);
49  EXPECT_EQ(f.type().typeSize(), 8);
50  EXPECT_EQ(f.isArray(), true);
51  EXPECT_EQ(f.arraySize(), 32);
52  EXPECT_EQ(f.name(), "my_array");
53 }
54 
55 TEST(RosType, builtin_dynamic_array)
56 {
57  ROSField f("float32[] my_array");
58 
59  EXPECT_EQ(f.type().baseName(), "float32");
60  EXPECT_EQ(f.type().msgName(), "float32");
61  EXPECT_EQ(f.type().pkgName().size(), 0 );
62  EXPECT_EQ(f.type().isBuiltin(), true);
63  EXPECT_EQ(f.type().typeSize(), 4);
64  EXPECT_EQ(f.isArray(), true);
65  EXPECT_EQ(f.arraySize(), -1);
66  EXPECT_EQ(f.name(), "my_array");
67 }
68 
69 
70 TEST(RosType, no_builtin_array)
71 {
72  ROSField f("geometry_msgs/Pose my_pose");
73 
74  EXPECT_EQ(f.type().baseName(), "geometry_msgs/Pose" );
75  EXPECT_EQ(f.type().msgName(), "Pose" );
76  EXPECT_EQ(f.type().pkgName(), "geometry_msgs" );
77  EXPECT_EQ(f.type().isBuiltin(), false);
78  EXPECT_EQ(f.type().typeSize(), -1);
79  EXPECT_EQ(f.isArray(), false);
80  EXPECT_EQ(f.arraySize(), 1);
81  EXPECT_EQ(f.name(), "my_pose");
82 }
83 
84 TEST(ROSMessageFields, ParseComments) {
85 
86  std::string
87  def("MSG: geometry_msgs/Quaternion\n"
88  "\n"
89  "#just a comment"
90  " # I'm a comment after whitespace\n"
91  "float64 x # I'm an end of line comment float64 y\n"
92  "float64 z\n"
93  );
94  ROSMessage mt(def);
95  EXPECT_EQ( mt.type().baseName(), "geometry_msgs/Quaternion" );
96 
97  EXPECT_EQ(mt.fields().size(), 2);
98  EXPECT_EQ(mt.field(0).type().msgName(), "float64");
99  EXPECT_EQ(mt.field(1).type().msgName(), "float64");
100  EXPECT_EQ(mt.field(0).name(), "x");
101  EXPECT_EQ(mt.field(1).name(), "z");
102 
103  EXPECT_EQ( mt.field(0).isConstant(), false);
104  EXPECT_EQ( mt.field(1).isConstant(), false);
105 }
106 
107 TEST(ROSMessageFields, constant_uint8)
108 {
109  ROSMessage msg("uint8 a = 66\n");
110 
111  EXPECT_EQ(msg.fields().size(), 1);
112  EXPECT_EQ( msg.field(0).name(), "a" );
113  EXPECT_EQ( msg.field(0).type().baseName(), "uint8" );
114  EXPECT_EQ( msg.field(0).isConstant(), true);
115  EXPECT_EQ(msg.field(0).value(), "66");
116 }
117 
118 TEST(ROSMessageFields, ConstantNavstatus )
119 {
121 
122  EXPECT_EQ( msg.fields().size(), 10);
123 
124  EXPECT_EQ( msg.field(0).name(), ("STATUS_NO_FIX") );
125  EXPECT_EQ( msg.field(0).type().baseName(), ("int8"));
126  EXPECT_EQ( msg.field(0).value(), ("-1"));
127 
128  EXPECT_EQ( msg.field(1).name(), ("STATUS_FIX") );
129  EXPECT_EQ( msg.field(1).type().baseName(), ("int8"));
130  EXPECT_EQ( msg.field(1).value() , ("0"));
131 
132  EXPECT_EQ( msg.field(2).name(), ("STATUS_SBAS_FIX") );
133  EXPECT_EQ( msg.field(2).type().baseName(), ("int8"));
134  EXPECT_EQ( msg.field(2).value() , ("1"));
135 
136  EXPECT_EQ( msg.field(3).name(), ("STATUS_GBAS_FIX") );
137  EXPECT_EQ( msg.field(3).type().baseName(), ("int8"));
138  EXPECT_EQ( msg.field(3).value() , ("2"));
139 
140  EXPECT_EQ( msg.field(4).name(), ("status") );
141  EXPECT_EQ( msg.field(4).type().baseName(), ("int8"));
142  EXPECT_EQ( msg.field(4).isConstant() , false);
143 
144  EXPECT_EQ( msg.field(5).name(), ("SERVICE_GPS") );
145  EXPECT_EQ( msg.field(5).type().baseName(), ("uint16"));
146  EXPECT_EQ( msg.field(5).value() , ("1"));
147 
148  EXPECT_EQ( msg.field(6).name(), ("SERVICE_GLONASS") );
149  EXPECT_EQ( msg.field(6).type().baseName(), ("uint16"));
150  EXPECT_EQ( msg.field(6).value() , ("2"));
151 
152  EXPECT_EQ( msg.field(7).name(), ("SERVICE_COMPASS") );
153  EXPECT_EQ( msg.field(7).type().baseName(), ("uint16"));
154  EXPECT_EQ( msg.field(7).value() , ("4"));
155 
156  EXPECT_EQ( msg.field(8).name(), ("SERVICE_GALILEO") );
157  EXPECT_EQ( msg.field(8).type().baseName(), ("uint16"));
158  EXPECT_EQ( msg.field(8).value() , ("8"));
159 
160  EXPECT_EQ( msg.field(9).name(), ("service") );
161  EXPECT_EQ( msg.field(9).type().baseName(), ("uint16"));
162  EXPECT_EQ( msg.field(9).isConstant() , false);
163 }
164 
165 
166 TEST(ROSMessageFields, ConstantComments )
167 {
168  ROSMessage msg(
169  "string strA= this string has a # comment in it \n"
170  "string strB = this string has \"quotes\" and \\slashes\\ in it\n"
171  "float64 a=64.0 # numeric comment\n");
172 
173 
174  EXPECT_EQ( msg.fields().size(), 3);
175  EXPECT_EQ( ("strA"), msg.field(0).name());
176  EXPECT_EQ( ("string"), msg.field(0).type().baseName() );
177  EXPECT_EQ( msg.field(0).isConstant(), true);
178  EXPECT_EQ( ("this string has a # comment in it"), msg.field(0).value());
179 
180  EXPECT_EQ( ("strB"), msg.field(1).name());
181  EXPECT_EQ( ("string"), msg.field(1).type().baseName() );
182  EXPECT_EQ( msg.field(1).isConstant(), true);
183  EXPECT_EQ( ("this string has \"quotes\" and \\slashes\\ in it"), msg.field(1).value());
184 
185  EXPECT_EQ( ("a"), msg.field(2).name());
186  EXPECT_EQ( ("float64"), msg.field(2).type().baseName() );
187  EXPECT_EQ( msg.field(2).isConstant(), true);
188  EXPECT_EQ( ("64.0"), msg.field(2).value());
189 }
190 
191 /*
192 TEST(BuildROSTypeMapFromDefinition, PoseParsing )
193 {
194  RosIntrospection::Parser parser;
195 
196  parser.registerMessageDefinition(
197  "pose",
198  ROSType(DataType<geometry_msgs::Pose >::value()),
199  Definition<geometry_msgs::Pose >::value());
200 
201  const ROSMessageInfo* info = parser.getMessageInfo("pose");
202  const ROSMessage* msg = &(info->type_list[0]);
203 
204  EXPECT_EQ( msg->type().baseName(), "geometry_msgs/Pose" );
205  EXPECT_EQ( msg->fields().size(), 2);
206  EXPECT_EQ( msg->field(0).type().baseName(), "geometry_msgs/Point" );
207  EXPECT_EQ( msg->field(0).name(), "position" );
208  EXPECT_EQ( msg->field(1).type().baseName(), "geometry_msgs/Quaternion" );
209  EXPECT_EQ( msg->field(1).name(), "orientation" );
210 
211  msg = &info->type_list[1];
212  EXPECT_EQ( ("geometry_msgs/Point" ), msg->type().baseName() );
213  EXPECT_EQ( msg->fields().size(), 3);
214  EXPECT_EQ( msg->field(0).type().baseName(), "float64" );
215  EXPECT_EQ( msg->field(0).name(), "x" );
216  EXPECT_EQ( msg->field(1).type().baseName(), "float64" );
217  EXPECT_EQ( msg->field(1).name(), "y" );
218  EXPECT_EQ( msg->field(2).type().baseName(), "float64" );
219  EXPECT_EQ( msg->field(2).name(), "z" );
220 
221  msg = &info->type_list[2];
222  EXPECT_EQ( ("geometry_msgs/Quaternion" ), msg->type().baseName() );
223  EXPECT_EQ( msg->fields().size(), 4);
224  EXPECT_EQ( msg->field(0).type().baseName(), "float64" );
225  EXPECT_EQ( msg->field(0).name(), "x" );
226  EXPECT_EQ( msg->field(1).type().baseName() , "float64" );
227  EXPECT_EQ( msg->field(1).name(), "y" );
228  EXPECT_EQ( msg->field(2).type().baseName() , "float64" );
229  EXPECT_EQ( msg->field(2).name(), "z" );
230  EXPECT_EQ( msg->field(3).type().baseName() , "float64" );
231  EXPECT_EQ( msg->field(3).name(), "w" );
232 }
233 */
234 TEST(BuildROSTypeMapFromDefinition, IMUparsing )
235 {
237 
239  "imu",
242 
243  const ROSMessageInfo* info = parser.getMessageInfo("imu");
244  const ROSMessage* msg = &info->type_list[0];
245  EXPECT_EQ( ("sensor_msgs/Imu"), msg->type().baseName() );
246  EXPECT_EQ( msg->fields().size(), 7);
247  EXPECT_EQ( ("std_msgs/Header" ), msg->field(0).type().baseName() );
248  EXPECT_EQ( ("header" ) , msg->field(0).name() );
249 
250  EXPECT_EQ( ("geometry_msgs/Quaternion" ), msg->field(1).type().baseName() );
251  EXPECT_EQ( ("orientation" ) , msg->field(1).name() );
252 
253  EXPECT_EQ( ("float64" ) , msg->field(2).type().baseName() );
254  EXPECT_EQ( ("orientation_covariance" ) , msg->field(2).name() );
255  EXPECT_EQ( msg->field(2).arraySize(), 9);
256 
257  EXPECT_EQ( ("geometry_msgs/Vector3" ), msg->field(3).type().baseName() );
258  EXPECT_EQ( ("angular_velocity" ) , msg->field(3).name() );
259 
260  EXPECT_EQ( ("float64" ) , msg->field(4).type().baseName() );
261  EXPECT_EQ( ("angular_velocity_covariance" ), msg->field(4).name() );
262  EXPECT_EQ( msg->field(4).arraySize(), 9);
263 
264  EXPECT_EQ( ("geometry_msgs/Vector3" ), msg->field(5).type().baseName() );
265  EXPECT_EQ( ("linear_acceleration" ) , msg->field(5).name() );
266 
267  EXPECT_EQ( ("float64" ) , msg->field(6).type().baseName() );
268  EXPECT_EQ( ("linear_acceleration_covariance" ), msg->field(6).name() );
269  EXPECT_EQ( msg->field(6).arraySize(), 9);
270 
271 
272  //---------------------------------
273  msg = &info->type_list[1];
274  EXPECT_EQ( msg->type().baseName(), "std_msgs/Header" );
275  EXPECT_EQ( msg->fields().size(), 3);
276  EXPECT_EQ( msg->field(0).type().baseName(), ("uint32" ));
277  EXPECT_EQ( msg->field(0).name(), ("seq") );
278  EXPECT_EQ( msg->field(1).type().baseName(), ("time") );
279  EXPECT_EQ( msg->field(1).name(), "stamp" );
280  EXPECT_EQ( msg->field(2).type().baseName(), "string" );
281  EXPECT_EQ( msg->field(2).name(), "frame_id" );
282 
283  msg = &info->type_list[2];
284  EXPECT_EQ( msg->type().baseName(), ("geometry_msgs/Quaternion") );
285  EXPECT_EQ( msg->fields().size(), 4);
286  EXPECT_EQ( msg->field(0).type().baseName(), "float64" );
287  EXPECT_EQ( msg->field(0).name(), "x" );
288  EXPECT_EQ( msg->field(1).type().baseName(), "float64" );
289  EXPECT_EQ( msg->field(1).name(), "y" );
290  EXPECT_EQ( msg->field(2).type().baseName(), "float64" );
291  EXPECT_EQ( msg->field(2).name(), "z" );
292  EXPECT_EQ( msg->field(3).type().baseName(), "float64" );
293  EXPECT_EQ( msg->field(3).name(), "w" );
294 
295  msg = &info->type_list[3];
296  EXPECT_EQ( msg->type().baseName(), ("geometry_msgs/Vector3") );
297  EXPECT_EQ( msg->fields().size(), 3);
298  EXPECT_EQ( msg->field(0).type().baseName(), "float64" );
299  EXPECT_EQ( msg->field(0).name(), "x" );
300  EXPECT_EQ( msg->field(1).type().baseName(), "float64" );
301  EXPECT_EQ( msg->field(1).name(), "y" );
302  EXPECT_EQ( msg->field(2).type().baseName(), "float64" );
303  EXPECT_EQ( msg->field(2).name(), "z" );
304 }
305 
306 TEST(BuildROSTypeMapFromDefinition, Int16MultiArrayParsing )
307 {
308  // this test case was added because it previously failed to detect nested
309  // arrays of custom types. In this case:
310  // std_msgs/MultiArrayDimension[]
311 
313 
314  parser.registerMessageDefinition( "multiarray",
317 
318 
319  /*std_msgs/Int16MultiArray :
320  layout : std_msgs/MultiArrayLayout
321  data : int16[]
322 
323  std_msgs/MultiArrayLayout :
324  dim : std_msgs/MultiArrayDimension[]
325  data_offset : uint32
326 
327  std_msgs/MultiArrayDimension :
328  label : string
329  size : uint32
330  stride : uint32*/
331 
332  const ROSMessageInfo* info = parser.getMessageInfo("multiarray");
333  const ROSMessage* msg = &info->type_list[0];
334 
335  EXPECT_EQ( ("std_msgs/Int16MultiArray"), msg->type().baseName() );
336  EXPECT_EQ( msg->fields().size(), 2);
337  EXPECT_EQ( ("std_msgs/MultiArrayLayout" ), msg->field(0).type().baseName() );
338  EXPECT_EQ( ("layout" ) , msg->field(0).name() );
339  EXPECT_EQ( false, msg->field(0).isArray() );
340 
341  EXPECT_EQ( ("int16" ), msg->field(1).type().baseName() );
342  EXPECT_EQ( ("data" ) , msg->field(1).name() );
343  EXPECT_EQ( true, msg->field(1).isArray() );
344 
345  msg = &info->type_list[1];
346  EXPECT_EQ( ("std_msgs/MultiArrayLayout"), msg->type().baseName() );
347  EXPECT_EQ( msg->fields().size(), 2);
348  EXPECT_EQ( ("std_msgs/MultiArrayDimension" ), msg->field(0).type().baseName() );
349  EXPECT_EQ( ("dim" ) , msg->field(0).name() );
350  EXPECT_EQ( true, msg->field(0).isArray() );
351 
352  EXPECT_EQ( ("uint32" ) , msg->field(1).type().baseName() );
353  EXPECT_EQ( ("data_offset" ) , msg->field(1).name() );
354  EXPECT_EQ( false, msg->field(1).isArray() );
355 
356 
357  msg = &info->type_list[2];
358  EXPECT_EQ( ("std_msgs/MultiArrayDimension"), msg->type().baseName() );
359  EXPECT_EQ( msg->fields().size(), 3);
360 
361  EXPECT_EQ( ("string" ), msg->field(0).type().baseName() );
362  EXPECT_EQ( ("label" ) , msg->field(0).name() );
363  EXPECT_EQ( false, msg->field(0).isArray() );
364 
365  EXPECT_EQ( ("uint32" ), msg->field(1).type().baseName() );
366  EXPECT_EQ( ("size" ) , msg->field(1).name() );
367  EXPECT_EQ( false, msg->field(1).isArray() );
368 
369  EXPECT_EQ( ("uint32" ) , msg->field(2).type().baseName() );
370  EXPECT_EQ( ("stride" ) , msg->field(2).name() );
371  EXPECT_EQ( false, msg->field(2).isArray() );
372 
373 }
374 
375 
376 
EXPECT_EQ(flat_container.value[index].first.toStdString(),("imu/header/seq"))
const ROSMessageInfo * getMessageInfo(const std::string &msg_identifier) const
const absl::string_view & pkgName() const
const std::string & value() const
f
const std::vector< ROSField > & fields() const
RosIntrospection::Parser parser
std::vector< ROSMessage > type_list
const std::string & name() const
const std::string & baseName() const
constexpr size_type size() const noexcept
const absl::string_view & msgName() const
const ROSField & field(size_t index) const
const ROSType & type() const
const ROSType & type() const
TEST(RosType, builtin_int32)
Definition: parser_test.cpp:13
const char * msg
void registerMessageDefinition(const std::string &message_identifier, const ROSType &main_type, const std::string &definition)


type_introspection_tests
Author(s): Davide Faconti
autogenerated on Fri Apr 13 2018 02:21:58