Skip to content

Commit

Permalink
URDF parser: use SDFormat 1.11, parse joint mimic
Browse files Browse the repository at this point in the history
Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters committed Oct 3, 2023
1 parent ea0d5ba commit be3a619
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 4 deletions.
14 changes: 13 additions & 1 deletion src/parser_urdf.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3148,6 +3148,18 @@ void CreateJoint(tinyxml2::XMLElement *_root,
AddKeyValue(jointAxisLimit, "velocity",
Values2str(1, &_link->parent_joint->limits->velocity));
}

if (_link->parent_joint->mimic)
{
tinyxml2::XMLElement *jointAxisMimic = doc->NewElement("mimic");
jointAxisMimic->SetAttribute(
"joint", _link->parent_joint->mimic->joint_name.c_str());
AddKeyValue(jointAxisMimic, "multiplier",
Values2str(1, &_link->parent_joint->mimic->multiplier));
AddKeyValue(jointAxisMimic, "offset",
Values2str(1, &_link->parent_joint->mimic->offset));
jointAxis->LinkEndChild(jointAxisMimic);
}
}

if (jtype == "fixed" && !fixedJointConvertedToRevoluteJoint)
Expand Down Expand Up @@ -3410,7 +3422,7 @@ void URDF2SDF::InitModelString(const std::string &_urdfStr,
{
// URDF is compatible with version 1.7. The automatic conversion script
// will up-convert URDF to SDF.
sdf->SetAttribute("version", "1.7");
sdf->SetAttribute("version", "1.11");
// add robot to sdf
sdf->LinkEndChild(robot);
}
Expand Down
6 changes: 3 additions & 3 deletions src/parser_urdf_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,8 @@ TEST(URDFParser, ParseResults_BasicModel_ParseEqualToModel)

// SDF -> SDF
std::ostringstream stream;
// parser_urdf.cc exports version "1.7"
stream << "<sdf version='" << "1.7" << "'>"
// parser_urdf.cc exports version "1.11"
stream << "<sdf version='" << "1.11" << "'>"
<< " <model name='test_robot' />"
<< "</sdf>";
tinyxml2::XMLDocument sdf_doc;
Expand Down Expand Up @@ -890,7 +890,7 @@ TEST(URDFParser, CheckJointTransform)
<< " </link>"
<< "</robot>";

std::string expectedSdf = R"(<sdf version="1.7">
std::string expectedSdf = R"(<sdf version="1.11">
<model name="test_robot">
<joint type="fixed" name="jointw_1">
<pose relative_to="__model__">0 0 0 0 0 0</pose>
Expand Down

0 comments on commit be3a619

Please sign in to comment.