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


type_introspection_tests
Author(s): Davide Faconti
autogenerated on Sat Apr 14 2018 03:30:59