Skip to content

Commit

Permalink
Do not automatically remove //axis/initial_position (#717)
Browse files Browse the repository at this point in the history
* Do not automatically remove //axis/initial_position

This allows the parser to emit a warning or an error if users still have
`//axis/initial_position` in their SDFormat files.

Signed-off-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
azeey authored Sep 28, 2021
1 parent 94ed817 commit 57badeb
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 14 deletions.
10 changes: 0 additions & 10 deletions sdf/1.9/1_8.convert
Original file line number Diff line number Diff line change
@@ -1,12 +1,2 @@
<convert name="sdf">

<!-- Remove //axis/initial_position and //axis2/initial_position -->
<convert descendant_name="joint">
<convert name="axis">
<remove element="initial_position"/>
</convert>
<convert name="axis2">
<remove element="initial_position"/>
</convert>
</convert>
</convert> <!-- End SDF -->
29 changes: 29 additions & 0 deletions src/parser_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -802,6 +802,35 @@ TEST(Parser, MissingRequiredElement)
EXPECT_EQ(errors[0].LineNumber().value(), 7);
}

TEST(Parser, ElementRemovedAfterDeprecation)
{
const std::string testString = R"(<?xml version="1.0" ?>
<sdf version="1.9">
<model name="test_model">
<link name="link_0"/>
<link name="link_1"/>
<joint name="joint" type="revolute">
<parent>link_0</parent>
<child>link_1</child>
<axis>
<initial_position>0.1</initial_position> <!-- Removed in 1.9 -->
</axis>
</joint>
</model>
</sdf>)";

sdf::Errors errors;
sdf::SDFPtr sdf = InitSDF();
sdf::ParserConfig config;
config.SetUnrecognizedElementsPolicy(sdf::EnforcementPolicy::ERR);
sdf::readString(testString, config, sdf, errors);

ASSERT_NE(errors.size(), 0u);
EXPECT_EQ(errors[0].Code(), sdf::ErrorCode::ELEMENT_INCORRECT_TYPE);
ASSERT_TRUE(errors[0].LineNumber().has_value());
EXPECT_EQ(errors[0].LineNumber().value(), 10);
}

/////////////////////////////////////////////////
/// Main
int main(int argc, char **argv)
Expand Down
4 changes: 0 additions & 4 deletions test/integration/joint_axis_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -108,10 +108,6 @@ TEST(DOMJointAxis, Complete)

EXPECT_DOUBLE_EQ(10.6, axis->SpringStiffness());
EXPECT_DOUBLE_EQ(0.0, axis2->SpringStiffness());

// Ensure that //axis/initial_position is removed during conversion
EXPECT_FALSE(axis->Element()->HasElement("initial_position"));
EXPECT_FALSE(axis2->Element()->HasElement("initial_position"));
}

//////////////////////////////////////////////////
Expand Down

0 comments on commit 57badeb

Please sign in to comment.