parser_test.cpp
Go to the documentation of this file.
00001 #include "config.h"
00002 #include <gtest/gtest.h>
00003 
00004 #include <geometry_msgs/Pose.h>
00005 #include <sensor_msgs/NavSatStatus.h>
00006 #include <sensor_msgs/Imu.h>
00007 #include <std_msgs/Int16MultiArray.h>
00008 #include <ros_type_introspection/parser.hpp>
00009 
00010 using namespace ros::message_traits;
00011 using namespace RosIntrospection;
00012 
00013 TEST(RosType, builtin_int32)
00014 {
00015   ROSType f("int32");
00016 
00017   EXPECT_EQ(f.baseName(), "int32");
00018   EXPECT_EQ(f.msgName(),  "int32");
00019   EXPECT_EQ(f.pkgName().size(),  0);
00020   EXPECT_EQ(f.isArray(),  false);
00021   EXPECT_EQ(f.isBuiltin(),  true);
00022   EXPECT_EQ(f.arraySize(),  1);
00023   EXPECT_EQ(f.typeSize(),  4);
00024 }
00025 
00026 TEST(RosType,  builtin_string)
00027 {
00028   ROSType f("string");
00029   EXPECT_EQ(f.baseName(),  "string");
00030   EXPECT_EQ(f.msgName() ,  "string");
00031   EXPECT_EQ(f.pkgName().size(),  0);
00032   EXPECT_EQ(f.isArray(),  false);
00033   EXPECT_EQ(f.isBuiltin(),  true);
00034   EXPECT_EQ(f.arraySize(),  1);
00035   EXPECT_EQ(f.typeSize(),  -1);
00036 }
00037 
00038 
00039 TEST(RosType, builtin_fixedlen_array)
00040 {
00041   ROSType f("float64[32]");
00042 
00043   EXPECT_EQ(f.baseName(),  "float64[32]");
00044   EXPECT_EQ(f.msgName(),  "float64");
00045   EXPECT_EQ(f.pkgName().size(),  0 );
00046   EXPECT_EQ(f.isArray(),  true);
00047   EXPECT_EQ(f.isBuiltin(),  true);
00048   EXPECT_EQ(f.arraySize(),  32);
00049   EXPECT_EQ(f.typeSize(),  8);
00050 }
00051 
00052 
00053 TEST(RosType, no_builtin_array)
00054 {
00055   ROSType f("geometry_msgs/Pose[]");
00056 
00057   EXPECT_EQ(f.baseName(),  "geometry_msgs/Pose[]" );
00058   EXPECT_EQ(f.msgName(),  "Pose" );
00059   EXPECT_EQ(f.pkgName(),  "geometry_msgs" );
00060   EXPECT_EQ(f.isArray(),  true);
00061   EXPECT_EQ(f.isBuiltin(),  false);
00062   EXPECT_EQ(f.arraySize(),  -1);
00063   EXPECT_EQ(f.typeSize(),  -1);
00064 }
00065 
00066 TEST(ROSMessageFields, ParseComments) {
00067 
00068   std::string
00069       def("MSG: geometry_msgs/Quaternion\n"
00070           "\n"
00071           "#just a comment"
00072           "          # I'm a comment after whitespace\n"
00073           "float64 x # I'm an end of line comment float64 y\n"
00074           "float64 z\n"
00075           );
00076   ROSMessage mt(def);
00077   EXPECT_EQ( mt.type().baseName(),  "geometry_msgs/Quaternion" );
00078 
00079   EXPECT_EQ( mt.fields().size(),  2);
00080   EXPECT_EQ(mt.field(0).type().msgName(),  "float64");
00081   EXPECT_EQ(mt.field(1).type().msgName(),  "float64");
00082   EXPECT_EQ(mt.field(0).name(),  "x");
00083   EXPECT_EQ(mt.field(1).name(),  "z");
00084 
00085   EXPECT_EQ( mt.field(0).isConstant(),  false);
00086   EXPECT_EQ( mt.field(1).isConstant(),  false);
00087 }
00088 
00089 TEST(ROSMessageFields, constant_uint8)
00090 {
00091   ROSMessage msg("uint8 a = 66\n");
00092 
00093   EXPECT_EQ(msg.fields().size(),  1);
00094   EXPECT_EQ( msg.field(0).name(),  "a" );
00095   EXPECT_EQ( msg.field(0).type().baseName(),  "uint8" );
00096   EXPECT_EQ( msg.field(0).isConstant(),  true);
00097   EXPECT_EQ(msg.field(0).value(),  "66");
00098 }
00099 
00100 TEST(ROSMessageFields, ConstantNavstatus )
00101 {
00102   ROSMessage msg( Definition<sensor_msgs::NavSatStatus >::value() );
00103 
00104   EXPECT_EQ( msg.fields().size(),  10);
00105 
00106   EXPECT_EQ( msg.field(0).name(), ("STATUS_NO_FIX") );
00107   EXPECT_EQ( msg.field(0).type().baseName(),  ("int8"));
00108   EXPECT_EQ( msg.field(0).value(), ("-1"));
00109 
00110   EXPECT_EQ( msg.field(1).name(),  ("STATUS_FIX") );
00111   EXPECT_EQ( msg.field(1).type().baseName(),  ("int8"));
00112   EXPECT_EQ( msg.field(1).value() ,  ("0"));
00113 
00114   EXPECT_EQ( msg.field(2).name(),  ("STATUS_SBAS_FIX") );
00115   EXPECT_EQ( msg.field(2).type().baseName(),  ("int8"));
00116   EXPECT_EQ( msg.field(2).value() ,  ("1"));
00117 
00118   EXPECT_EQ( msg.field(3).name(),  ("STATUS_GBAS_FIX") );
00119   EXPECT_EQ( msg.field(3).type().baseName(),  ("int8"));
00120   EXPECT_EQ( msg.field(3).value() ,  ("2"));
00121 
00122   EXPECT_EQ( msg.field(4).name(),  ("status") );
00123   EXPECT_EQ( msg.field(4).type().baseName(),  ("int8"));
00124   EXPECT_EQ( msg.field(4).isConstant() ,  false);
00125 
00126   EXPECT_EQ( msg.field(5).name(),  ("SERVICE_GPS") );
00127   EXPECT_EQ( msg.field(5).type().baseName(),  ("uint16"));
00128   EXPECT_EQ( msg.field(5).value() ,  ("1"));
00129 
00130   EXPECT_EQ( msg.field(6).name(),  ("SERVICE_GLONASS") );
00131   EXPECT_EQ( msg.field(6).type().baseName(),  ("uint16"));
00132   EXPECT_EQ( msg.field(6).value() ,  ("2"));
00133 
00134   EXPECT_EQ( msg.field(7).name(),  ("SERVICE_COMPASS") );
00135   EXPECT_EQ( msg.field(7).type().baseName(),  ("uint16"));
00136   EXPECT_EQ( msg.field(7).value() ,  ("4"));
00137 
00138   EXPECT_EQ( msg.field(8).name(),  ("SERVICE_GALILEO") );
00139   EXPECT_EQ( msg.field(8).type().baseName(),  ("uint16"));
00140   EXPECT_EQ( msg.field(8).value() ,  ("8"));
00141 
00142   EXPECT_EQ( msg.field(9).name(),  ("service") );
00143   EXPECT_EQ( msg.field(9).type().baseName(),  ("uint16"));
00144   EXPECT_EQ( msg.field(9).isConstant() ,  false);
00145 }
00146 
00147 
00148 TEST(ROSMessageFields, ConstantComments )
00149 {
00150   ROSMessage msg(
00151         "string strA=  this string has a # comment in it  \n"
00152         "string strB = this string has \"quotes\" and \\slashes\\ in it\n"
00153         "float64 a=64.0 # numeric comment\n");
00154 
00155 
00156   EXPECT_EQ( msg.fields().size(),  3);
00157   EXPECT_EQ( ("strA"), msg.field(0).name());
00158   EXPECT_EQ( ("string"), msg.field(0).type().baseName() );
00159   EXPECT_EQ( msg.field(0).isConstant(),  true);
00160   EXPECT_EQ( ("this string has a # comment in it"),  msg.field(0).value());
00161 
00162   EXPECT_EQ( ("strB"),  msg.field(1).name());
00163   EXPECT_EQ( ("string"), msg.field(1).type().baseName() );
00164   EXPECT_EQ( msg.field(1).isConstant(),  true);
00165   EXPECT_EQ( ("this string has \"quotes\" and \\slashes\\ in it"),   msg.field(1).value());
00166 
00167   EXPECT_EQ( ("a"), msg.field(2).name());
00168   EXPECT_EQ( ("float64"), msg.field(2).type().baseName() );
00169   EXPECT_EQ( msg.field(2).isConstant(),  true);
00170   EXPECT_EQ( ("64.0"), msg.field(2).value());
00171 }
00172 
00173 
00174 TEST(buildROSTypeMapFromDefinition,  PoseParsing )
00175 {
00176   RosIntrospection::ROSTypeList rmap;
00177 
00178   rmap = buildROSTypeMapFromDefinition(
00179         DataType<geometry_msgs::Pose >::value(),
00180         Definition<geometry_msgs::Pose >::value());
00181 
00182   if(VERBOSE_TEST){ std::cout << rmap << std::endl; }
00183 
00184   ROSMessage& msg = rmap.at(0);
00185   EXPECT_EQ( msg.type().baseName(),  "geometry_msgs/Pose" );
00186   EXPECT_EQ( msg.fields().size(),  2);
00187   EXPECT_EQ( msg.field(0).type().baseName(),  "geometry_msgs/Point" );
00188   EXPECT_EQ( msg.field(0).name(),  "position" );
00189   EXPECT_EQ( msg.field(1).type().baseName(),  "geometry_msgs/Quaternion" );
00190   EXPECT_EQ( msg.field(1).name(),  "orientation" );
00191 
00192   msg = rmap.at(1);
00193   EXPECT_EQ( ("geometry_msgs/Point" ),  msg.type().baseName() );
00194   EXPECT_EQ( msg.fields().size(),  3);
00195   EXPECT_EQ( msg.field(0).type().baseName(),  "float64" );
00196   EXPECT_EQ( msg.field(0).name(),  "x" );
00197   EXPECT_EQ( msg.field(1).type().baseName(),  "float64" );
00198   EXPECT_EQ( msg.field(1).name(),  "y" );
00199   EXPECT_EQ( msg.field(2).type().baseName(),  "float64" );
00200   EXPECT_EQ( msg.field(2).name(),  "z" );
00201 
00202   msg = rmap.at(2);
00203   EXPECT_EQ( ("geometry_msgs/Quaternion" ),  msg.type().baseName() );
00204   EXPECT_EQ( msg.fields().size(),  4);
00205   EXPECT_EQ( msg.field(0).type().baseName(),  "float64" );
00206   EXPECT_EQ( msg.field(0).name(),  "x" );
00207   EXPECT_EQ( msg.field(1).type().baseName() ,  "float64" );
00208   EXPECT_EQ( msg.field(1).name(),  "y" );
00209   EXPECT_EQ( msg.field(2).type().baseName() ,  "float64" );
00210   EXPECT_EQ( msg.field(2).name(),  "z" );
00211   EXPECT_EQ( msg.field(3).type().baseName() ,  "float64" );
00212   EXPECT_EQ( msg.field(3).name(),  "w" );
00213 }
00214 
00215 TEST(buildROSTypeMapFromDefinition,  IMUparsing )
00216 {
00217   RosIntrospection::ROSTypeList rmap;
00218 
00219   rmap = buildROSTypeMapFromDefinition(
00220         DataType<sensor_msgs::Imu >::value(),
00221         Definition<sensor_msgs::Imu >::value());
00222 
00223   if(VERBOSE_TEST){ std::cout << rmap << std::endl; }
00224 
00225   ROSMessage& msg = rmap.at(0);
00226   EXPECT_EQ( ("sensor_msgs/Imu"),  msg.type().baseName() );
00227   EXPECT_EQ( msg.fields().size(),  7);
00228   EXPECT_EQ( ("std_msgs/Header" ),  msg.field(0).type().baseName() );
00229   EXPECT_EQ( ("header" )         ,  msg.field(0).name() );
00230 
00231   EXPECT_EQ( ("geometry_msgs/Quaternion" ),  msg.field(1).type().baseName() );
00232   EXPECT_EQ( ("orientation" )             ,  msg.field(1).name() );
00233 
00234   EXPECT_EQ( ("float64[9]" )             ,  msg.field(2).type().baseName() );
00235   EXPECT_EQ( ("orientation_covariance" ) ,  msg.field(2).name() );
00236   EXPECT_EQ( msg.field(2).type().arraySize(),  9);
00237 
00238   EXPECT_EQ( ("geometry_msgs/Vector3" ),  msg.field(3).type().baseName() );
00239   EXPECT_EQ( ("angular_velocity" )     ,  msg.field(3).name() );
00240 
00241   EXPECT_EQ( ("float64[9]" )                 ,  msg.field(4).type().baseName() );
00242   EXPECT_EQ( ("angular_velocity_covariance" ),  msg.field(4).name() );
00243   EXPECT_EQ( msg.field(4).type().arraySize(),  9);
00244 
00245   EXPECT_EQ( ("geometry_msgs/Vector3" ),  msg.field(5).type().baseName() );
00246   EXPECT_EQ( ("linear_acceleration" )  ,  msg.field(5).name() );
00247 
00248   EXPECT_EQ( ("float64[9]" )                    ,  msg.field(6).type().baseName() );
00249   EXPECT_EQ( ("linear_acceleration_covariance" ),  msg.field(6).name() );
00250   EXPECT_EQ( msg.field(6).type().arraySize(),  9);
00251 
00252 
00253   //---------------------------------
00254   msg = rmap.at(1);
00255   EXPECT_EQ( msg.type().baseName(),  "std_msgs/Header" );
00256   EXPECT_EQ( msg.fields().size(),  3);
00257   EXPECT_EQ( msg.field(0).type().baseName(),  ("uint32" ));
00258   EXPECT_EQ( msg.field(0).name(),  ("seq") );
00259   EXPECT_EQ( msg.field(1).type().baseName(),  ("time") );
00260   EXPECT_EQ( msg.field(1).name(),  "stamp" );
00261   EXPECT_EQ( msg.field(2).type().baseName(),  "string" );
00262   EXPECT_EQ( msg.field(2).name(),  "frame_id" );
00263 
00264   msg = rmap.at(2);
00265   EXPECT_EQ( msg.type().baseName(),  ("geometry_msgs/Quaternion") );
00266   EXPECT_EQ( msg.fields().size(),  4);
00267   EXPECT_EQ( msg.field(0).type().baseName(),  "float64" );
00268   EXPECT_EQ( msg.field(0).name(),  "x" );
00269   EXPECT_EQ( msg.field(1).type().baseName(),  "float64" );
00270   EXPECT_EQ( msg.field(1).name(),  "y" );
00271   EXPECT_EQ( msg.field(2).type().baseName(),  "float64" );
00272   EXPECT_EQ( msg.field(2).name(),  "z" );
00273   EXPECT_EQ( msg.field(3).type().baseName(),  "float64" );
00274   EXPECT_EQ( msg.field(3).name(),  "w" );
00275 
00276   msg = rmap.at(3);
00277   EXPECT_EQ( msg.type().baseName(),  ("geometry_msgs/Vector3") );
00278   EXPECT_EQ( msg.fields().size(),  3);
00279   EXPECT_EQ( msg.field(0).type().baseName(),  "float64" );
00280   EXPECT_EQ( msg.field(0).name(),  "x" );
00281   EXPECT_EQ( msg.field(1).type().baseName(),  "float64" );
00282   EXPECT_EQ( msg.field(1).name(),  "y" );
00283   EXPECT_EQ( msg.field(2).type().baseName(),  "float64" );
00284   EXPECT_EQ( msg.field(2).name(),  "z" );
00285 }
00286 
00287 TEST(buildROSTypeMapFromDefinition,  Int16MultiArrayParsing )
00288 {
00289   // this test case was added because it previously failed to detect nested
00290   // arrays of custom types. In this case:
00291   //    std_msgs/MultiArrayDimension[]
00292 
00293   RosIntrospection::ROSTypeList rmap;
00294 
00295   rmap = buildROSTypeMapFromDefinition(
00296         DataType<std_msgs::Int16MultiArray >::value(),
00297         Definition<std_msgs::Int16MultiArray >::value());
00298 
00299   if(VERBOSE_TEST){
00300     std::cout << rmap << std::endl;
00301   }
00302 
00303   /*std_msgs/Int16MultiArray :
00304           layout : std_msgs/MultiArrayLayout
00305           data : int16[]
00306 
00307       std_msgs/MultiArrayLayout :
00308           dim : std_msgs/MultiArrayDimension[]
00309           data_offset : uint32
00310 
00311       std_msgs/MultiArrayDimension :
00312           label : string
00313           size : uint32
00314           stride : uint32*/
00315 
00316   ROSMessage& msg = rmap.at(0);
00317 
00318   EXPECT_EQ( ("std_msgs/Int16MultiArray"),  msg.type().baseName() );
00319   EXPECT_EQ( msg.fields().size(),  2);
00320   EXPECT_EQ( ("std_msgs/MultiArrayLayout" ),  msg.field(0).type().baseName() );
00321   EXPECT_EQ( ("layout" )                   ,  msg.field(0).name() );
00322   EXPECT_EQ( false,  msg.field(0).type().isArray() );
00323 
00324   EXPECT_EQ( ("int16[]" ),  msg.field(1).type().baseName() );
00325   EXPECT_EQ( ("data" ) ,  msg.field(1).name() );
00326   EXPECT_EQ( true,  msg.field(1).type().isArray() );
00327 
00328   msg = rmap.at(1);
00329   EXPECT_EQ( ("std_msgs/MultiArrayLayout"),  msg.type().baseName() );
00330   EXPECT_EQ( msg.fields().size(),  2);
00331   EXPECT_EQ( ("std_msgs/MultiArrayDimension[]" ),  msg.field(0).type().baseName() );
00332   EXPECT_EQ( ("dim" )                           ,  msg.field(0).name() );
00333   EXPECT_EQ( true,  msg.field(0).type().isArray() );
00334 
00335   EXPECT_EQ( ("uint32" )      ,  msg.field(1).type().baseName() );
00336   EXPECT_EQ( ("data_offset" ) ,  msg.field(1).name() );
00337   EXPECT_EQ( false,  msg.field(1).type().isArray() );
00338 
00339 
00340   msg = rmap.at(2);
00341   EXPECT_EQ( ("std_msgs/MultiArrayDimension"),  msg.type().baseName() );
00342   EXPECT_EQ( msg.fields().size(),  3);
00343 
00344   EXPECT_EQ( ("string" ),  msg.field(0).type().baseName() );
00345   EXPECT_EQ( ("label" )  ,  msg.field(0).name() );
00346   EXPECT_EQ( false,  msg.field(0).type().isArray() );
00347 
00348   EXPECT_EQ( ("uint32" ),  msg.field(1).type().baseName() );
00349   EXPECT_EQ( ("size" )  ,  msg.field(1).name() );
00350   EXPECT_EQ( false,  msg.field(1).type().isArray() );
00351 
00352   EXPECT_EQ( ("uint32" ) ,  msg.field(2).type().baseName() );
00353   EXPECT_EQ( ("stride" ) ,  msg.field(2).name() );
00354   EXPECT_EQ( false,  msg.field(2).type().isArray() );
00355 
00356 }
00357 
00358 // Run all the tests that were declared with TEST()
00359 int main(int argc, char **argv){
00360   testing::InitGoogleTest(&argc, argv);
00361   return RUN_ALL_TESTS();
00362 }
00363 


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Sun Oct 1 2017 02:54:53