Skip to content

Commit

Permalink
Respond to review comments
Browse files Browse the repository at this point in the history
* Check for tinyxml2 parsing errors
* Simplify map logic
* Add comments to example URDF
* Assert point is valid in test
* Remove outdated comment

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters committed Sep 28, 2022
1 parent 8b3c2ad commit 2e9f08e
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 9 deletions.
14 changes: 6 additions & 8 deletions src/parser_urdf.cc
Original file line number Diff line number Diff line change
Expand Up @@ -432,6 +432,11 @@ void ReduceFixedJoints(TiXmlElement *_root, urdf::LinkSharedPtr _link)
{
TiXmlDocument xmlNewDoc;
xmlNewDoc.Parse(_frame.c_str());
if (xmlNewDoc.Error())
{
sdferr << "Error while parsing serialized frames: "
<< xmlNewDoc.ErrorDesc() << '\n';
}

TiXmlElementPtr blob =
std::make_shared<TiXmlElement>(*xmlNewDoc.FirstChildElement());
Expand All @@ -440,15 +445,8 @@ void ReduceFixedJoints(TiXmlElement *_root, urdf::LinkSharedPtr _link)
stringToExtension(ssj.str());
stringToExtension(ssl.str());

// Ensure model extension vector is allocated
if (g_extensions.find("") == g_extensions.end())
{
std::vector<SDFExtensionPtr> ge;
g_extensions.insert(std::make_pair("", ge));
}

// Add //frame tags to model extension vector
g_extensions.at("").push_back(sdfExt);
g_extensions[""].push_back(sdfExt);

// lump sdf extensions to parent, (give them new reference _link names)
ReduceSDFExtensionToParent(_link);
Expand Down
4 changes: 4 additions & 0 deletions test/integration/fixed_joint_example.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<robot name="fixed_joint_example">

<link name="base">
<!-- base has inertial and visual geometry of a half-cube -->
<inertial>
<mass value="6"/>
<origin rpy="0 0 0" xyz="0 0 0.25"/>
Expand All @@ -22,6 +23,7 @@
<child link="intermediate_link"/>
</joint>
<link name="intermediate_link">
<!-- intermediate_link has inertial and visual geometry of a half-cube -->
<inertial>
<mass value="6"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
Expand All @@ -43,6 +45,8 @@
<child link="rotary_link"/>
</joint>
<link name="rotary_link">
<!-- rotary_link has inertial and visual geometry of a cube equivalent to the
merged properties of base and intermediate_link. -->
<inertial>
<mass value="12"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
Expand Down
2 changes: 1 addition & 1 deletion test/integration/urdf_gazebo_extensions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ TEST(SDFParser, UrdfGazeboExtensionURDFTest)
}

auto modelDom = root.ModelByIndex(0);
ASSERT_NE(nullptr, modelDom);
sdf::ElementPtr model = modelDom->Element();
for (sdf::ElementPtr joint = model->GetElement("joint"); joint;
joint = joint->GetNextElement("joint"))
Expand Down Expand Up @@ -401,7 +402,6 @@ TEST(SDFParser, FixedJointSimple)
EXPECT_EQ(1u, model->LinkCount());
EXPECT_TRUE(model->LinkNameExists("base"));

// Expect MassMatrix3 values to match for links
auto link = model->LinkByName("base");
ASSERT_NE(nullptr, link);
auto massMatrix = link->Inertial().MassMatrix();
Expand Down

0 comments on commit 2e9f08e

Please sign in to comment.