Skip to content

Commit

Permalink
Prefix nested model names when flattening (#399)
Browse files Browse the repository at this point in the history
Currently the addNestedModel function in parser.cc prefixes
link, joint, and frame names with the flattened model name
delimited by "::". This applies the same prefix to the names
of nested models within the flattened model as well.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters authored and azeey committed Nov 25, 2020
1 parent 8cef85f commit f5c8bd9
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 1 deletion.
3 changes: 2 additions & 1 deletion src/parser.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1285,6 +1285,7 @@ void addNestedModel(ElementPtr _sdf, ElementPtr _includeSDF, Errors &_errors)
while (elem)
{
if ((elem->GetName() == "link") ||
(elem->GetName() == "model") ||
(elem->GetName() == "joint") ||
(elem->GetName() == "frame"))
{
Expand All @@ -1293,7 +1294,7 @@ void addNestedModel(ElementPtr _sdf, ElementPtr _includeSDF, Errors &_errors)
replace[elemName] = newName;
}

if ((elem->GetName() == "link"))
if ((elem->GetName() == "link") || (elem->GetName() == "model"))
{
// Add a pose element even if the element doesn't originally have one
auto elemPose = elem->GetElement("pose");
Expand Down
6 changes: 6 additions & 0 deletions test/integration/model/test_model_with_frames/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -59,5 +59,11 @@
<parent>L3</parent>
<child>L4</child>
</joint>
<model name="M2">
<pose relative_to="F1">1 0 0 0 0 0</pose>
<link name="L5">
<pose>1 0 0 0 0 0</pose>
</link>
</model>
</model>
</sdf>
6 changes: 6 additions & 0 deletions test/integration/nested_model_with_frames_expected.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,12 @@
<parent>M1::L3</parent>
<child>M1::L4</child>
</joint>
<model name='M1::M2'>
<pose relative_to='M1::F1'>1 0 0 0 -0 0</pose>
<link name='L5'>
<pose>1 0 0 0 -0 0</pose>
</link>
</model>
</model>
</world>
</sdf>
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,12 @@
<parent>M1::test_model_with_frames::L3</parent>
<child>M1::test_model_with_frames::L4</child>
</joint>
<model name='M1::test_model_with_frames::M2'>
<pose relative_to='M1::test_model_with_frames::F1'>1 0 0 0 -0 0</pose>
<link name='L5'>
<pose>1 0 0 0 -0 0</pose>
</link>
</model>
</model>
</world>
</sdf>

0 comments on commit f5c8bd9

Please sign in to comment.