Skip to content

Commit

Permalink
Add a failing test showing behavior when mesh calculator callback is …
Browse files Browse the repository at this point in the history
…not set

Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey committed Sep 27, 2023
1 parent 4b1112e commit c550e3d
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 0 deletions.
10 changes: 10 additions & 0 deletions test/integration/root_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -300,3 +300,13 @@ TEST(DOMRoot, CreateMulipleWorlds)
testFunc(root);
testFunc(root2);
}

/////////////////////////////////////////////////
TEST(DOMRoot, LoadWithoutMeshAutoInertialCalculator)
{
const std::string testFile =
sdf::testing::TestFile("sdf", "mesh_auto_inertial.sdf");
sdf::Root root;
sdf::Errors errors = root.Load(testFile);
EXPECT_TRUE(errors.empty()) << errors;
}
17 changes: 17 additions & 0 deletions test/sdf/mesh_auto_inertial.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0" ?>
<!-- Since sdformat itself doesn't have an moment of inertia calculator for meshes, this file is not expected to load without errors -->
<sdf version='1.11'>
<model name='test_model'>
<link name='L1'>
<inertial auto='true'/>
<collision name="collision">
<geometry>
<mesh>
<uri>box.dae</uri>
</mesh>
</geometry>
</collision>
</link>
</model>
</sdf>

0 comments on commit c550e3d

Please sign in to comment.