Skip to content

Commit

Permalink
Add partially_flattened.sdf example and test
Browse files Browse the repository at this point in the history
Add test showing that Model::ModelByName and Model::ModelNameExists
have trouble with model names that contain "::" with TODO
comments to remind that they should be fixed.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters committed Oct 26, 2020
1 parent c44f822 commit 93658c3
Show file tree
Hide file tree
Showing 2 changed files with 75 additions and 0 deletions.
62 changes: 62 additions & 0 deletions test/integration/model_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -299,6 +299,68 @@ TEST(DOMRoot, MultiNestedModel)
EXPECT_NE(nullptr, outerModel->FrameByName(innerFrameNestedName));
}

////////////////////////////////////////////////
TEST(DOMRoot, PartiallyFlattenedModel)
{
const std::string testFile =
sdf::filesystem::append(PROJECT_SOURCE_PATH, "test", "sdf",
"partially_flattened.sdf");

// Load the SDF file
sdf::Root root;
auto errors = root.Load(testFile);
EXPECT_TRUE(errors.empty());

EXPECT_EQ(1u, root.ModelCount());

// Get the outer model
const sdf::Model *outerModel = root.ModelByIndex(0);
ASSERT_NE(nullptr, outerModel);
EXPECT_EQ("MP", outerModel->Name());
EXPECT_EQ(1u, outerModel->LinkCount());
EXPECT_NE(nullptr, outerModel->LinkByIndex(0));
EXPECT_EQ(nullptr, outerModel->LinkByIndex(1));

EXPECT_TRUE(outerModel->LinkNameExists("M1::L1"));

EXPECT_EQ(0u, outerModel->JointCount());

EXPECT_EQ(1u, outerModel->FrameCount());
EXPECT_TRUE(outerModel->FrameNameExists("M1::__model__"));

EXPECT_EQ(1u, outerModel->ModelCount());
EXPECT_NE(nullptr, outerModel->ModelByIndex(0));
EXPECT_EQ(nullptr, outerModel->ModelByIndex(1));

// Get the middle model
const sdf::Model *midModel = outerModel->ModelByIndex(0);
ASSERT_NE(nullptr, midModel);
EXPECT_EQ("M1::M2", midModel->Name());
// TODO: the following expectations should be true, but ModelNameExists
// and ModelByName do not support names containing "::".
// EXPECT_TRUE(outerModel->ModelNameExists("M1::M2"));
// EXPECT_EQ(midModel, outerModel->ModelByName("M1::M2"));

EXPECT_EQ(1u, midModel->LinkCount());
EXPECT_NE(nullptr, midModel->LinkByIndex(0));
EXPECT_EQ(nullptr, midModel->LinkByIndex(1));

EXPECT_TRUE(midModel->LinkNameExists("L2"));

EXPECT_EQ(0u, midModel->JointCount());

EXPECT_EQ(0u, midModel->FrameCount());

EXPECT_EQ(0u, midModel->ModelCount());

// test nested names from outer model
// TODO: the following expectations also fail due to the limitations of
// ModelNameExists and ModelByName not supporting names containing "::".
// const std::string midLinkNestedName = "M1::M2::L2";
// EXPECT_TRUE(outerModel->LinkNameExists(midLinkNestedName));
// EXPECT_NE(nullptr, outerModel->LinkByName(midLinkNestedName));
}

/////////////////////////////////////////////////
TEST(DOMLink, NestedModelPoseRelativeTo)
{
Expand Down
13 changes: 13 additions & 0 deletions test/sdf/partially_flattened.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<sdf version='1.7'>
<model name='MP'>
<frame name='M1::__model__' attached_to='M1::L1'>
<pose relative_to='__model__'>0 0 0 0 -0 0</pose>
</frame>
<link name='M1::L1'>
<pose relative_to='M1::__model__'>0 0 0 0 -0 0</pose>
</link>
<model name='M1::M2'> <!-- This is actually be M2 in the output. I think it's a bug -->
<link name='L2'/>
</model>
</model>
</sdf>

0 comments on commit 93658c3

Please sign in to comment.