@@ -2463,7 +2463,7 @@ TEST(URDFParser, ZeroMassLeafLink)
2463
2463
// ///////////////////////////////////////////////
2464
2464
TEST (URDFParser, ParseGazeboRefDoesntExistWarningMessage)
2465
2465
{
2466
- // Redirect sdfwarn output
2466
+ // Redirect sdfwarn output
2467
2467
std::stringstream buffer;
2468
2468
sdf::testing::RedirectConsoleStream redir (
2469
2469
sdf::Console::Instance ()->GetMsgStream (), &buffer);
@@ -2476,46 +2476,45 @@ TEST(URDFParser, ParseGazeboRefDoesntExistWarningMessage)
2476
2476
});
2477
2477
#endif
2478
2478
2479
- // test if reference to link exists
2480
- {
2481
- // clear the contents of the buffer
2479
+ // test if reference to link exists
2480
+ {
2481
+ // clear the contents of the buffer
2482
2482
buffer.str (" " );
2483
2483
2484
2484
std::string str = R"(
2485
- <robot name="test_robot">
2486
- <link name="link1">
2487
- <inertial>
2488
- <mass value="1" />
2489
- <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
2490
- </inertial>
2491
- </link>
2492
- <gazebo reference="lіnk1">
2493
- <sensor name="link1_imu" type="imu">
2494
- <always_on>1</always_on>
2495
- <update_rate>100</update_rate>
2496
- <pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
2497
- <plugin name="sensor_plugin" filename="example_plugin.so" />
2498
- </sensor>
2499
- </gazebo>
2500
- </robot>
2501
- )" ;
2485
+ <robot name="test_robot">
2486
+ <link name="link1">
2487
+ <inertial>
2488
+ <mass value="1" />
2489
+ <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
2490
+ </inertial>
2491
+ </link>
2492
+ <gazebo reference="lіnk1">
2493
+ <sensor name="link1_imu" type="imu">
2494
+ <always_on>1</always_on>
2495
+ <update_rate>100</update_rate>
2496
+ <pose>0.13525 0 -0.07019999999999993 0.0 -0.0 -2.0943952105869315</pose>
2497
+ <plugin name="sensor_plugin" filename="example_plugin.so" />
2498
+ </sensor>
2499
+ </gazebo>
2500
+ </robot>)" ;
2502
2501
2503
2502
sdf::URDF2SDF parser;
2504
2503
tinyxml2::XMLDocument sdfResult;
2505
2504
sdf::ParserConfig config;
2506
2505
parser.InitModelString (str, config, &sdfResult);
2507
-
2508
- EXPECT_PRED2 (sdf::testing::contains, buffer.str (),
2509
- " <gazebo> tag with reference[link1] does not exist in the URDF model. Please "
2510
- " ensure that the referenced attribute matches the name of a link, consider checking unicode "
2511
- " representation for reference attribute in case of invisible characters and homoglyphs " );
2512
- }
2513
-
2514
- // TODO: Similar tests for -
2515
- // InsertSDFExtensionCollision,
2516
- // InsertSDFExtensionRobot,
2517
- // InsertSDFExtensionVisual,
2518
- // InsertSDFExtensionJoint
2506
+
2507
+ EXPECT_PRED2 (sdf::testing::contains, buffer.str (),
2508
+ " <gazebo> tag with reference[" << _linkName << " ] does not exist "
2509
+ " in the URDF model. Please ensure that the reference attribute "
2510
+ " matches the name of a link. " );
2511
+ }
2512
+
2513
+ /* TODO(aagrawal05) : Similar tests for -
2514
+ InsertSDFExtensionCollision,
2515
+ InsertSDFExtensionRobot,
2516
+ InsertSDFExtensionVisual,
2517
+ InsertSDFExtensionJoint */
2519
2518
}
2520
2519
2521
2520
// ///////////////////////////////////////////////
0 commit comments