Skip to content

Commit 3151bd8

Browse files
aaronchongthazeey
andauthored
Fix bug where a sdf::ParserConfig object was not passed to all sdf::readFile calls (#824)
This fixes potential errors when loading nested models where the file search path was set using `sdf::ParserConfig::SetFindCallback` or `sdf::ParserConfig::AddURIPath`. Signed-off-by: Addisu Z. Taddese <addisu@openrobotics.org> Co-authored-by: Addisu Z. Taddese <addisu@openrobotics.org>
1 parent c80d78d commit 3151bd8

File tree

8 files changed

+72
-1
lines changed

8 files changed

+72
-1
lines changed

src/parser.cc

+1-1
Original file line numberDiff line numberDiff line change
@@ -1573,7 +1573,7 @@ bool readXml(tinyxml2::XMLElement *_xml, ElementPtr _sdf,
15731573
SDFPtr includeSDF(new SDF);
15741574
includeSDF->Root(includeSDFTemplate->Root()->Clone());
15751575

1576-
if (!readFile(filename, includeSDF))
1576+
if (!readFile(filename, _config, includeSDF, _errors))
15771577
{
15781578
Error err(
15791579
ErrorCode::FILE_READ,
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
<?xml version="1.0"?>
2+
3+
<model>
4+
<name>simple_model</name>
5+
<sdf version="1.9">model.sdf</sdf>
6+
</model>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
<?xml version="1.0" ?>
2+
<sdf version="1.9">
3+
4+
<model name="simple_model">
5+
<link name="link"/>
6+
</model>
7+
8+
</sdf>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
<?xml version="1.0"?>
2+
3+
<model>
4+
<name>sub_nested</name>
5+
<sdf version="1.9">model.sdf</sdf>
6+
</model>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
<?xml version="1.0" ?>
2+
<sdf version="1.9">
3+
4+
<model name="sub_nested">
5+
<include>
6+
<name>simple_model</name>
7+
<uri>simple_model</uri>
8+
</include>
9+
10+
<include>
11+
<name>extra_model</name>
12+
<uri>simple_model</uri>
13+
</include>
14+
</model>
15+
16+
</sdf>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
<?xml version="1.0"?>
2+
3+
<model>
4+
<name>top_nested</name>
5+
<sdf version="1.9">model.sdf</sdf>
6+
</model>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
<?xml version="1.0" ?>
2+
<sdf version="1.9">
3+
4+
<model name="top_nested">
5+
<include>
6+
<uri>sub_nested</uri>
7+
</include>
8+
</model>
9+
10+
</sdf>

test/integration/parser_config.cc

+19
Original file line numberDiff line numberDiff line change
@@ -239,3 +239,22 @@ TEST(ParserConfig, ParseWithNonGlobalConfig)
239239
}
240240
}
241241
}
242+
243+
/////////////////////////////////////////////////
244+
/// Test for ParserConfig being passed down when parsing nested models
245+
TEST(ParserConfig, NestedModelIncludesFilePath)
246+
{
247+
const auto path =
248+
sdf::testing::TestFile("integration", "model", "top_nested", "model.sdf");
249+
250+
auto findFileCb = [](const std::string &_uri)
251+
{
252+
return sdf::testing::TestFile("integration", "model", _uri);
253+
};
254+
sdf::ParserConfig config;
255+
config.SetFindCallback(findFileCb);
256+
257+
sdf::Root root;
258+
sdf::Errors errors = root.Load(path, config);
259+
EXPECT_TRUE(errors.empty()) << errors;
260+
}

0 commit comments

Comments
 (0)