Skip to content

Commit 6b53f95

Browse files
authored
9 ➡️ 10 (#795)
Signed-off-by: Louise Poubel <louise@openrobotics.org>
2 parents 251c354 + e5c29da commit 6b53f95

4 files changed

Lines changed: 311 additions & 0 deletions

File tree

src/parser.cc

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1416,6 +1416,7 @@ void addNestedModel(ElementPtr _sdf, ElementPtr _includeSDF, Errors &_errors)
14161416
}
14171417

14181418
_includeSDF->ClearElements();
1419+
_includeSDF->RemoveAllAttributes();
14191420
readString(str, _includeSDF, _errors);
14201421

14211422
elem = _includeSDF->GetElement("model")->GetFirstElement();
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
<?xml version="1.0"?>
2+
<model>
3+
<name>model_with_custom_elements</name>
4+
<sdf version="1.7">model.sdf</sdf>
5+
</model>
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
<?xml version="1.0" ?>
2+
<sdf version="1.7" xmlns:mysim="http://example.org/mysim/schema">
3+
<model name="M1">
4+
<link name="L1" mysim:custom_attr_str="A" mysim:custom_attr_int="5" />
5+
<link name="L2" />
6+
<joint name="J1" type="revolute">
7+
<parent>L1</parent>
8+
<child>L2</child>
9+
</joint>
10+
11+
<model name="M2">
12+
<link name="L1" mysim:custom_attr_str="B">
13+
<mysim:transmission name="simple_trans">
14+
<mysim:type>transmission_interface/SimpleTransmission</mysim:type>
15+
<mysim:joint name="J1">
16+
<mysim:hardwareInterface>EffortJointInterface</mysim:hardwareInterface>
17+
</mysim:joint>
18+
</mysim:transmission>
19+
</link>
20+
</model>
21+
</model>
22+
</sdf>

test/integration/sdf_custom.cc

Lines changed: 283 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -82,3 +82,286 @@ TEST(SDFParser, CustomElements)
8282
tranJointElement->Get<std::string>("mysim:hardwareInterface");
8383
EXPECT_EQ("EffortJointInterface", tranHwInterface);
8484
}
85+
86+
/////////////////////////////////////////////////
87+
TEST(SDFParser, ReloadCustomElements)
88+
{
89+
const std::string sdfTestFile =
90+
sdf::testing::TestFile("integration", "custom_elems_attrs.sdf");
91+
92+
// load file with custom elements
93+
sdf::Root root1;
94+
sdf::Errors errors = root1.Load(sdfTestFile);
95+
EXPECT_TRUE(errors.empty());
96+
97+
// reload string output of root1
98+
sdf::Root root2;
99+
errors = root2.LoadSdfString(root1.Element()->ToString(""));
100+
EXPECT_TRUE(errors.empty());
101+
102+
// check that root1 and root2 equal
103+
const sdf::World *world1 = root1.WorldByIndex(0);
104+
const sdf::World *world2 = root2.WorldByIndex(0);
105+
ASSERT_NE(nullptr, world1);
106+
ASSERT_NE(nullptr, world2);
107+
108+
const sdf::Model *model1 = world1->ModelByIndex(0);
109+
const sdf::Model *model2 = world2->ModelByIndex(0);
110+
ASSERT_NE(nullptr, model1);
111+
ASSERT_NE(nullptr, model2);
112+
EXPECT_EQ(model1->Element()->ToString(""), model2->Element()->ToString(""));
113+
114+
const sdf::Link *link1 = model1->LinkByIndex(0);
115+
const sdf::Link *link2 = model2->LinkByIndex(0);
116+
ASSERT_NE(nullptr, link1);
117+
ASSERT_NE(nullptr, link2);
118+
EXPECT_EQ(link1->Element()->ToString(""), link2->Element()->ToString(""));
119+
120+
sdf::ElementPtr customElem1 =
121+
model1->Element()->FindElement("mysim:transmission");
122+
sdf::ElementPtr customElem2 =
123+
model2->Element()->FindElement("mysim:transmission");
124+
ASSERT_NE(nullptr, customElem1);
125+
ASSERT_NE(nullptr, customElem2);
126+
127+
const std::string customElemStr =
128+
R"(<mysim:transmission name='simple_trans'>
129+
<mysim:type>transmission_interface/SimpleTransmission</mysim:type>
130+
<mysim:joint name='J1'>
131+
<mysim:hardwareInterface>EffortJointInterface</mysim:hardwareInterface>
132+
</mysim:joint>
133+
</mysim:transmission>
134+
)";
135+
EXPECT_EQ(customElemStr, customElem1->ToString(""));
136+
EXPECT_EQ(customElemStr, customElem2->ToString(""));
137+
138+
sdf::ElementPtr customDesc1 =
139+
world1->Element()->FindElement("mysim:description");
140+
sdf::ElementPtr customDesc2 =
141+
world2->Element()->FindElement("mysim:description");
142+
ASSERT_NE(nullptr, customDesc1);
143+
ASSERT_NE(nullptr, customDesc2);
144+
145+
const std::string customDescStr =
146+
"<mysim:description>Description of this world</mysim:description>\n";
147+
EXPECT_EQ(customDescStr, customDesc1->ToString(""));
148+
EXPECT_EQ(customDescStr, customDesc2->ToString(""));
149+
}
150+
151+
/////////////////////////////////////////////////
152+
TEST(SDFParser, ReloadIncludedCustomElements)
153+
{
154+
const std::string modelPath = sdf::testing::TestFile("integration", "model");
155+
156+
sdf::setFindCallback(
157+
[&](const std::string &_file)
158+
{
159+
return sdf::filesystem::append(modelPath, _file);
160+
});
161+
162+
const std::string sdfStr =
163+
R"(<sdf version='1.7'>
164+
<world name='default'>
165+
<include>
166+
<uri>model_with_custom_elements</uri>
167+
</include>
168+
</world>
169+
</sdf>
170+
)";
171+
172+
// load included file with custom elements
173+
sdf::Root root1;
174+
sdf::Errors errors = root1.LoadSdfString(sdfStr);
175+
EXPECT_TRUE(errors.empty());
176+
177+
// reload string output of root1
178+
sdf::Root root2;
179+
errors = root2.LoadSdfString(root1.Element()->ToString(""));
180+
EXPECT_TRUE(errors.empty());
181+
182+
// check that root1 and root2 equal
183+
EXPECT_EQ(root1.Element()->ToString(""), root2.Element()->ToString(""));
184+
185+
const sdf::World *world1 = root1.WorldByIndex(0);
186+
const sdf::World *world2 = root2.WorldByIndex(0);
187+
ASSERT_NE(nullptr, world1);
188+
ASSERT_NE(nullptr, world2);
189+
190+
// //model[@name=M1]
191+
const sdf::Model *model11 = world1->ModelByIndex(0);
192+
const sdf::Model *model12 = world2->ModelByIndex(0);
193+
ASSERT_NE(nullptr, model11);
194+
ASSERT_NE(nullptr, model12);
195+
EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString(""));
196+
197+
// //model[@name=M1]/link[@name=L1]
198+
const sdf::Link *model11link1 = model11->LinkByIndex(0);
199+
const sdf::Link *model12link2 = model12->LinkByIndex(0);
200+
ASSERT_NE(nullptr, model11link1);
201+
ASSERT_NE(nullptr, model12link2);
202+
203+
const std::string linkCustomAttrStr =
204+
"<link name='L1' mysim:custom_attr_str='A' mysim:custom_attr_int='5'/>\n";
205+
EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString(""));
206+
EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString(""));
207+
208+
// //model[@name=M1]/model[@name=M2]
209+
const sdf::Model *model21 = model11->ModelByIndex(0);
210+
const sdf::Model *model22 = model12->ModelByIndex(0);
211+
ASSERT_NE(nullptr, model21);
212+
ASSERT_NE(nullptr, model22);
213+
EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString(""));
214+
215+
// //model[@name=M1]/model[@name=M2]/link[@name=L1]
216+
const sdf::Link *model21link1 = model21->LinkByIndex(0);
217+
const sdf::Link *model22link2 = model22->LinkByIndex(0);
218+
ASSERT_NE(nullptr, model21link1);
219+
ASSERT_NE(nullptr, model22link2);
220+
EXPECT_EQ(model21link1->Element()->ToString(""),
221+
model22link2->Element()->ToString(""));
222+
223+
// check custom attributes
224+
sdf::ParamPtr param1 =
225+
model21link1->Element()->GetAttribute("mysim:custom_attr_str");
226+
sdf::ParamPtr param2 =
227+
model22link2->Element()->GetAttribute("mysim:custom_attr_str");
228+
ASSERT_NE(nullptr, param1);
229+
ASSERT_NE(nullptr, param2);
230+
EXPECT_EQ("B", param1->GetAsString());
231+
EXPECT_EQ("B", param2->GetAsString());
232+
233+
// //model[@name=M1]/model[@name=M2]/link[@name=L1]/mysim:transmission
234+
sdf::ElementPtr customElem1 =
235+
model21link1->Element()->FindElement("mysim:transmission");
236+
sdf::ElementPtr customElem2 =
237+
model22link2->Element()->FindElement("mysim:transmission");
238+
ASSERT_NE(nullptr, customElem1);
239+
ASSERT_NE(nullptr, customElem2);
240+
241+
const std::string customElemStr =
242+
R"(<mysim:transmission name='simple_trans'>
243+
<mysim:type>transmission_interface/SimpleTransmission</mysim:type>
244+
<mysim:joint name='J1'>
245+
<mysim:hardwareInterface>EffortJointInterface</mysim:hardwareInterface>
246+
</mysim:joint>
247+
</mysim:transmission>
248+
)";
249+
EXPECT_EQ(customElemStr, customElem1->ToString(""));
250+
EXPECT_EQ(customElemStr, customElem2->ToString(""));
251+
}
252+
253+
/////////////////////////////////////////////////
254+
TEST(SDFParser, ReloadNestedIncludedCustomElements)
255+
{
256+
const std::string modelPath = sdf::testing::TestFile("integration", "model");
257+
258+
sdf::setFindCallback(
259+
[&](const std::string &_file)
260+
{
261+
return sdf::filesystem::append(modelPath, _file);
262+
});
263+
264+
const std::string sdfStr =
265+
R"(<sdf version='1.7'>
266+
<world name='default'>
267+
<model name='test'>
268+
<include>
269+
<uri>model_with_custom_elements</uri>
270+
</include>
271+
</model>
272+
</world>
273+
</sdf>
274+
)";
275+
276+
sdf::Root root1;
277+
sdf::Errors errors = root1.LoadSdfString(sdfStr);
278+
EXPECT_TRUE(errors.empty());
279+
280+
for (auto &e : errors)
281+
std::cout << e.Message() << std::endl;
282+
283+
sdf::Root root2;
284+
errors = root2.LoadSdfString(root1.Element()->ToString(""));
285+
EXPECT_TRUE(errors.empty());
286+
287+
// check that root1 and root2 equal
288+
EXPECT_EQ(root1.Element()->ToString(""), root2.Element()->ToString(""));
289+
290+
const sdf::World *world1 = root1.WorldByIndex(0);
291+
const sdf::World *world2 = root2.WorldByIndex(0);
292+
ASSERT_NE(nullptr, world1);
293+
ASSERT_NE(nullptr, world2);
294+
295+
// //model[@name=test]
296+
const sdf::Model *model11 = world1->ModelByIndex(0);
297+
const sdf::Model *model12 = world2->ModelByIndex(0);
298+
ASSERT_NE(nullptr, model11);
299+
ASSERT_NE(nullptr, model12);
300+
EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString(""));
301+
302+
// //model[@name=test]/frame[@name=M1::__model__]
303+
const sdf::Frame *frame1 = model11->FrameByIndex(0);
304+
const sdf::Frame *frame2 = model12->FrameByIndex(0);
305+
ASSERT_NE(nullptr, frame1);
306+
ASSERT_NE(nullptr, frame2);
307+
EXPECT_EQ(frame1->Element()->ToString(""), frame2->Element()->ToString(""));
308+
309+
// //model[@name=test]/link[@name=M1::L1]
310+
const sdf::Link *model11link1 = model11->LinkByIndex(0);
311+
const sdf::Link *model12link2 = model12->LinkByIndex(0);
312+
ASSERT_NE(nullptr, model11link1);
313+
ASSERT_NE(nullptr, model12link2);
314+
315+
const std::string linkCustomAttrStr =
316+
R"(<link name='M1::L1' mysim:custom_attr_str='A' mysim:custom_attr_int='5'>
317+
<pose relative_to='M1::__model__'>0 0 0 0 -0 0</pose>
318+
</link>
319+
)";
320+
EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString(""));
321+
EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString(""));
322+
323+
// //model[@name=test]/model[@name=M1::M2]
324+
const sdf::Model *model21 = model11->ModelByIndex(0);
325+
const sdf::Model *model22 = model12->ModelByIndex(0);
326+
ASSERT_NE(nullptr, model21);
327+
ASSERT_NE(nullptr, model22);
328+
EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString(""));
329+
330+
// //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1]
331+
const sdf::Link *model21link1 = model21->LinkByIndex(0);
332+
const sdf::Link *model22link2 = model22->LinkByIndex(0);
333+
ASSERT_NE(nullptr, model21link1);
334+
ASSERT_NE(nullptr, model22link2);
335+
EXPECT_EQ(model21link1->Element()->ToString(""),
336+
model22link2->Element()->ToString(""));
337+
338+
// check custom attributes
339+
sdf::ParamPtr param1 =
340+
model21link1->Element()->GetAttribute("mysim:custom_attr_str");
341+
sdf::ParamPtr param2 =
342+
model22link2->Element()->GetAttribute("mysim:custom_attr_str");
343+
ASSERT_NE(nullptr, param1);
344+
ASSERT_NE(nullptr, param2);
345+
EXPECT_EQ("B", param1->GetAsString());
346+
EXPECT_EQ("B", param2->GetAsString());
347+
348+
// //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1]
349+
// /mysim:transmission
350+
sdf::ElementPtr customElem1 =
351+
model21link1->Element()->FindElement("mysim:transmission");
352+
sdf::ElementPtr customElem2 =
353+
model22link2->Element()->FindElement("mysim:transmission");
354+
ASSERT_NE(nullptr, customElem1);
355+
ASSERT_NE(nullptr, customElem2);
356+
357+
const std::string customElemStr =
358+
R"(<mysim:transmission name='simple_trans'>
359+
<mysim:type>transmission_interface/SimpleTransmission</mysim:type>
360+
<mysim:joint name='M1::J1'>
361+
<mysim:hardwareInterface>EffortJointInterface</mysim:hardwareInterface>
362+
</mysim:joint>
363+
</mysim:transmission>
364+
)";
365+
EXPECT_EQ(customElemStr, customElem1->ToString(""));
366+
EXPECT_EQ(customElemStr, customElem2->ToString(""));
367+
}

0 commit comments

Comments
 (0)