Skip to content

Commit

Permalink
Rename state elements when converting to 1.12
Browse files Browse the repository at this point in the history
Update some existing tests to verify conversion logic.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters committed Mar 1, 2024
1 parent 818b8f3 commit dd2054f
Show file tree
Hide file tree
Showing 3 changed files with 65 additions and 21 deletions.
44 changes: 44 additions & 0 deletions sdf/1.12/1_11.convert
Original file line number Diff line number Diff line change
@@ -1,2 +1,46 @@
<convert name="sdf">

<convert name="world">
<!-- Rename state elements -->
<convert name="state">

<move>
<from element="light"/>
<to element="light_state"/>
</move>

<move>
<from element="model"/>
<to element="model_state"/>
</move>

<convert name="model">
<move>
<from element="link"/>
<to element="link_state"/>
</move>
<move>
<from element="model"/>
<to element="model_state"/>
</move>
<convert name="model">
<move>
<from element="link"/>
<to element="link_state"/>
</move>
<move>
<from element="model"/>
<to element="model_state"/>
</move>
<convert name="model">
<move>
<from element="link"/>
<to element="link_state"/>
</move>
</convert>
</convert>
</convert>

</convert>
</convert>
</convert> <!-- End SDF -->
16 changes: 8 additions & 8 deletions test/integration/frame.cc
Original file line number Diff line number Diff line change
Expand Up @@ -206,11 +206,11 @@ TEST(Frame, NoFrame)
}

////////////////////////////////////////
// Test parsing nested model states
// Test parsing states with //pose/@relative_to
TEST(Frame, StateFrame)
{
std::ostringstream sdfStr;
sdfStr << "<sdf version ='" << SDF_VERSION << "'>"
sdfStr << "<sdf version ='1.11'>"
<< "<world name='default'>"
<< "<state world_name='default'>"
<< "<model name='my_model'>"
Expand Down Expand Up @@ -239,8 +239,8 @@ TEST(Frame, StateFrame)
EXPECT_TRUE(worldElem->HasElement("state"));
sdf::ElementPtr stateElem = worldElem->GetElement("state");

EXPECT_TRUE(stateElem->HasElement("model"));
sdf::ElementPtr modelStateElem = stateElem->GetElement("model");
EXPECT_TRUE(stateElem->HasElement("model_state"));
sdf::ElementPtr modelStateElem = stateElem->GetElement("model_state");

// model
EXPECT_TRUE(modelStateElem->HasAttribute("name"));
Expand Down Expand Up @@ -271,8 +271,8 @@ TEST(Frame, StateFrame)
}

// link
EXPECT_TRUE(modelStateElem->HasElement("link"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link");
EXPECT_TRUE(modelStateElem->HasElement("link_state"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link_state");
EXPECT_TRUE(linkStateElem->HasAttribute("name"));
EXPECT_EQ(linkStateElem->Get<std::string>("name"), "my_link");

Expand All @@ -286,8 +286,8 @@ TEST(Frame, StateFrame)
gz::math::Pose3d(111, 3, 0, 0, 0, 0));
}

EXPECT_TRUE(stateElem->HasElement("light"));
sdf::ElementPtr lightStateElem = stateElem->GetElement("light");
EXPECT_TRUE(stateElem->HasElement("light_state"));
sdf::ElementPtr lightStateElem = stateElem->GetElement("light_state");

// light
EXPECT_TRUE(lightStateElem->HasAttribute("name"));
Expand Down
26 changes: 13 additions & 13 deletions test/integration/nested_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ TEST(NestedModel, NestedModel)
TEST(NestedModel, State)
{
std::ostringstream sdfStr;
sdfStr << "<sdf version ='" << SDF_VERSION << "'>"
sdfStr << "<sdf version ='1.11'>"
<< "<world name='default'>"
<< "<state world_name='default'>"
<< "<model name='model_00'>"
Expand Down Expand Up @@ -154,9 +154,9 @@ TEST(NestedModel, State)
sdf::ElementPtr worldElem = sdfParsed->Root()->GetElement("world");
EXPECT_TRUE(worldElem->HasElement("state"));
sdf::ElementPtr stateElem = worldElem->GetElement("state");
EXPECT_TRUE(stateElem->HasElement("model"));
EXPECT_TRUE(stateElem->HasElement("model_state"));

sdf::ElementPtr modelStateElem = stateElem->GetElement("model");
sdf::ElementPtr modelStateElem = stateElem->GetElement("model_state");

// model sdf
EXPECT_TRUE(modelStateElem->HasAttribute("name"));
Expand All @@ -167,8 +167,8 @@ TEST(NestedModel, State)
EXPECT_TRUE(!modelStateElem->HasElement("joint"));

// link sdf
EXPECT_TRUE(modelStateElem->HasElement("link"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link");
EXPECT_TRUE(modelStateElem->HasElement("link_state"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link_state");
EXPECT_TRUE(linkStateElem->HasAttribute("name"));
EXPECT_EQ(linkStateElem->Get<std::string>("name"), "link_00");
EXPECT_TRUE(linkStateElem->HasElement("pose"));
Expand All @@ -185,9 +185,9 @@ TEST(NestedModel, State)
gz::math::Pose3d(0, 0.006121, 0, 0, 0, 0));

// nested model sdf
EXPECT_TRUE(modelStateElem->HasElement("model"));
EXPECT_TRUE(modelStateElem->HasElement("model_state"));
sdf::ElementPtr nestedModelStateElem =
modelStateElem->GetElement("model");
modelStateElem->GetElement("model_state");
EXPECT_TRUE(nestedModelStateElem->HasAttribute("name"));
EXPECT_EQ(nestedModelStateElem->Get<std::string>("name"), "model_01");
EXPECT_TRUE(nestedModelStateElem->HasElement("pose"));
Expand All @@ -196,9 +196,9 @@ TEST(NestedModel, State)
EXPECT_TRUE(!nestedModelStateElem->HasElement("joint"));

// nested model's link sdf
EXPECT_TRUE(nestedModelStateElem->HasElement("link"));
EXPECT_TRUE(nestedModelStateElem->HasElement("link_state"));
sdf::ElementPtr nestedLinkStateElem =
nestedModelStateElem->GetElement("link");
nestedModelStateElem->GetElement("link_state");
EXPECT_TRUE(nestedLinkStateElem->HasAttribute("name"));
EXPECT_EQ(nestedLinkStateElem->Get<std::string>("name"), "link_01");
EXPECT_TRUE(nestedLinkStateElem->HasElement("pose"));
Expand All @@ -215,8 +215,8 @@ TEST(NestedModel, State)
gz::math::Pose3d(0, 0.000674, 0, 0, 0, 0));

// double nested model sdf
EXPECT_TRUE(nestedModelStateElem->HasElement("model"));
nestedModelStateElem = nestedModelStateElem->GetElement("model");
EXPECT_TRUE(nestedModelStateElem->HasElement("model_state"));
nestedModelStateElem = nestedModelStateElem->GetElement("model_state");
EXPECT_TRUE(nestedModelStateElem->HasAttribute("name"));
EXPECT_EQ(nestedModelStateElem->Get<std::string>("name"), "model_02");
EXPECT_TRUE(nestedModelStateElem->HasElement("pose"));
Expand All @@ -225,8 +225,8 @@ TEST(NestedModel, State)
EXPECT_TRUE(!nestedModelStateElem->HasElement("joint"));

// double nested model's link sdf
EXPECT_TRUE(nestedModelStateElem->HasElement("link"));
nestedLinkStateElem = nestedModelStateElem->GetElement("link");
EXPECT_TRUE(nestedModelStateElem->HasElement("link_state"));
nestedLinkStateElem = nestedModelStateElem->GetElement("link_state");
EXPECT_TRUE(nestedLinkStateElem->HasAttribute("name"));
EXPECT_EQ(nestedLinkStateElem->Get<std::string>("name"), "link_02");
EXPECT_TRUE(nestedLinkStateElem->HasElement("pose"));
Expand Down

0 comments on commit dd2054f

Please sign in to comment.