Skip to content

Commit

Permalink
Add tests showing problems with conversion
Browse files Browse the repository at this point in the history
The Converter currently only acts on the first child
element it finds; it doesn't act on all sibling elements.
I've added example SDFormat files and tests to illustrate
the issue.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters committed Mar 1, 2024
1 parent dd2054f commit e9de659
Show file tree
Hide file tree
Showing 3 changed files with 265 additions and 0 deletions.
96 changes: 96 additions & 0 deletions test/integration/nested_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -243,6 +243,102 @@ TEST(NestedModel, State)
gz::math::Pose3d(0, 0, 0, 0, 0, 0));
}

////////////////////////////////////////
// Test parsing nested model states
TEST(NestedModel, StateSiblingsConversion1_12)
{
const std::string testFile =
sdf::testing::TestFile("sdf", "state_nested_model_world.sdf");

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

// load the state sdf
EXPECT_TRUE(root.Element()->HasElement("world"));
sdf::ElementPtr worldElem = root.Element()->GetElement("world");

// Confirm that regular model elements were not migrated
EXPECT_FALSE(worldElem->HasElement("model_state"));

// Confirm that model and link elements in state were converted to
// model_state and link_state
EXPECT_TRUE(worldElem->HasElement("state"));
sdf::ElementPtr stateElem = worldElem->GetElement("state");
EXPECT_TRUE(stateElem->HasElement("model_state"))
<< stateElem->ToString("");
EXPECT_FALSE(stateElem->HasElement("model"))
<< stateElem->ToString("");

// model sdf
sdf::ElementPtr modelStateElem = stateElem->GetElement("model_state");
EXPECT_TRUE(modelStateElem->HasAttribute("name"));
EXPECT_EQ(modelStateElem->Get<std::string>("name"), "top_level_model");
EXPECT_TRUE(modelStateElem->HasElement("link_state"))
<< modelStateElem->ToString("");
EXPECT_TRUE(modelStateElem->HasElement("model_state"))
<< modelStateElem->ToString("");
EXPECT_FALSE(modelStateElem->HasElement("link"))
<< modelStateElem->ToString("");
EXPECT_FALSE(modelStateElem->HasElement("model"))
<< modelStateElem->ToString("");
}

////////////////////////////////////////
// Test parsing nested model states
TEST(NestedModel, StateInsertionsConversion1_12)
{
const std::string testFile =
sdf::testing::TestFile("sdf", "state_nested_model_world_insertion.sdf");

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

// load the state sdf
EXPECT_TRUE(root.Element()->HasElement("world"));
sdf::ElementPtr worldElem = root.Element()->GetElement("world");

// Confirm that regular model elements were not migrated
EXPECT_FALSE(worldElem->HasElement("model_state"));

// Confirm that model and link elements in state were converted to
// model_state and link_state
EXPECT_TRUE(worldElem->HasElement("state"));
sdf::ElementPtr stateElem = worldElem->GetElement("state");
EXPECT_TRUE(stateElem->HasElement("model_state"))
<< stateElem->ToString("");
EXPECT_FALSE(stateElem->HasElement("model"))
<< stateElem->ToString("");

// model sdf
sdf::ElementPtr modelStateElem = stateElem->GetElement("model_state");
EXPECT_TRUE(modelStateElem->HasAttribute("name"));
EXPECT_EQ(modelStateElem->Get<std::string>("name"), "top_level_model");
EXPECT_TRUE(modelStateElem->HasElement("link_state"))
<< modelStateElem->ToString("");
EXPECT_TRUE(modelStateElem->HasElement("model_state"))
<< modelStateElem->ToString("");
EXPECT_FALSE(modelStateElem->HasElement("link"))
<< modelStateElem->ToString("");
EXPECT_FALSE(modelStateElem->HasElement("model"))
<< modelStateElem->ToString("");

// insertions
EXPECT_TRUE(stateElem->HasElement("insertions"));
sdf::ElementPtr insertionsElem = stateElem->GetElement("insertions");
// confirm that //insertions/model and link tags were not converted
EXPECT_FALSE(insertionsElem->HasElement("model_state"));
EXPECT_TRUE(insertionsElem->HasElement("model"));
sdf::ElementPtr insertedModelElem = insertionsElem->GetElement("model");
EXPECT_TRUE(insertedModelElem->HasAttribute("name"));
EXPECT_EQ(insertedModelElem->Get<std::string>("name"), "unit_box");
EXPECT_FALSE(insertedModelElem->HasElement("link_state"));
EXPECT_TRUE(insertedModelElem->HasElement("link"));
}

////////////////////////////////////////
// Test parsing models with joints nested via <include>
// Confirm that joint axis rotation is handled differently for 1.4 and 1.5+
Expand Down
79 changes: 79 additions & 0 deletions test/sdf/state_nested_model_world.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
<?xml version="1.0"?>
<sdf version="1.7">
<world name="default">
<model name="top_level_model">
<link name="parent"/>
<link name="child"/>
<model name="nested_model01">
<link name="nested_link01"/>
<link name="nested_link02"/>
<model name="nested_nested_model01">
<link name="nested_nested_link01"/>
<link name="nested_nested_link02"/>
</model>
<model name="nested_nested_model02">
<link name="nested_nested_link01"/>
<link name="nested_nested_link02"/>
</model>
</model>
<model name="nested_model02">
<link name="nested_link01"/>
<link name="nested_link02"/>
</model>
<joint name="top_level_joint" type="revolute">
<parent>parent</parent>
<child>child</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
</model>
<gravity>0 0 -9.8</gravity>
<state world_name="default">
<sim_time>0 689000000</sim_time>
<real_time>0 732670244</real_time>
<wall_time>1709252095 646182343</wall_time>
<iterations>689</iterations>
<model name="top_level_model">
<link name="child">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="parent">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<model name="nested_model01">
<link name="nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<model name="nested_nested_model01">
<link name="nested_nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
</model>
<model name="nested_nested_model02">
<link name="nested_nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
</model>
</model>
<model name="nested_model02">
<link name="nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
</model>
</model>
</state>
</world>
</sdf>
90 changes: 90 additions & 0 deletions test/sdf/state_nested_model_world_insertion.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
<?xml version="1.0"?>
<sdf version="1.7">
<world name="default">
<model name="top_level_model">
<link name="parent"/>
<link name="child"/>
<model name="nested_model01">
<link name="nested_link01"/>
<link name="nested_link02"/>
<model name="nested_nested_model01">
<link name="nested_nested_link01"/>
<link name="nested_nested_link02"/>
</model>
<model name="nested_nested_model02">
<link name="nested_nested_link01"/>
<link name="nested_nested_link02"/>
</model>
</model>
<model name="nested_model02">
<link name="nested_link01"/>
<link name="nested_link02"/>
</model>
<joint name="top_level_joint" type="revolute">
<parent>parent</parent>
<child>child</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
</model>
<gravity>0 0 -9.8</gravity>
<state world_name="default">
<sim_time>0 689000000</sim_time>
<real_time>0 732670244</real_time>
<wall_time>1709252095 646182343</wall_time>
<iterations>689</iterations>
<insertions>
<model name='unit_box'>
<pose>-0.541687 -2.44761 0.5 0 -0 0</pose>
<link name='link'/>
</model>
</insertions>
<model name="top_level_model">
<link name="child">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="parent">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<model name="nested_model01">
<link name="nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<model name="nested_nested_model01">
<link name="nested_nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
</model>
<model name="nested_nested_model02">
<link name="nested_nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
</model>
</model>
<model name="nested_model02">
<link name="nested_link01">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
<link name="nested_link02">
<pose>0 0 -2.329 0 -0 0 </pose>
</link>
</model>
</model>
<model name="unit_box">
<link name="link">
<pose>-0.5417 -2.448 0.5 0 -0 0 </pose>
</link>
</model>
</state>
</world>
</sdf>

0 comments on commit e9de659

Please sign in to comment.