2 #include <gtest/gtest.h> 4 #include <geometry_msgs/Pose.h> 5 #include <sensor_msgs/NavSatStatus.h> 6 #include <sensor_msgs/Imu.h> 7 #include <std_msgs/Int16MultiArray.h> 13 TEST(RosType, builtin_int32)
27 TEST(RosType, builtin_string)
41 TEST(RosType, builtin_fixedlen_array)
55 TEST(RosType, builtin_dynamic_array)
70 TEST(RosType, no_builtin_array)
84 TEST(ROSMessageFields, ParseComments) {
87 def(
"MSG: geometry_msgs/Quaternion\n" 90 " # I'm a comment after whitespace\n" 91 "float64 x # I'm an end of line comment float64 y\n" 107 TEST(ROSMessageFields, constant_uint8)
118 TEST(ROSMessageFields, ConstantNavstatus )
166 TEST(ROSMessageFields, ConstantComments )
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");
234 TEST(BuildROSTypeMapFromDefinition, IMUparsing )
274 EXPECT_EQ( msg->type().baseName(),
"std_msgs/Header" );
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" );
284 EXPECT_EQ( msg->type().baseName(), (
"geometry_msgs/Quaternion") );
286 EXPECT_EQ( msg->field(0).type().baseName(),
"float64" );
288 EXPECT_EQ( msg->field(1).type().baseName(),
"float64" );
290 EXPECT_EQ( msg->field(2).type().baseName(),
"float64" );
292 EXPECT_EQ( msg->field(3).type().baseName(),
"float64" );
296 EXPECT_EQ( msg->type().baseName(), (
"geometry_msgs/Vector3") );
298 EXPECT_EQ( msg->field(0).type().baseName(),
"float64" );
300 EXPECT_EQ( msg->field(1).type().baseName(),
"float64" );
302 EXPECT_EQ( msg->field(2).type().baseName(),
"float64" );
306 TEST(BuildROSTypeMapFromDefinition, Int16MultiArrayParsing )
346 EXPECT_EQ( (
"std_msgs/MultiArrayLayout"), msg->type().baseName() );
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() );
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() );
358 EXPECT_EQ( (
"std_msgs/MultiArrayDimension"), msg->type().baseName() );
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() );
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() );
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() );
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
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)
void registerMessageDefinition(const std::string &message_identifier, const ROSType &main_type, const std::string &definition)