diff --git a/src/parser.cc b/src/parser.cc
index 85c1837b8..afb781704 100644
--- a/src/parser.cc
+++ b/src/parser.cc
@@ -1373,6 +1373,7 @@ void addNestedModel(ElementPtr _sdf, ElementPtr _includeSDF, Errors &_errors)
}
_includeSDF->ClearElements();
+ _includeSDF->RemoveAllAttributes();
readString(str, _includeSDF, _errors);
elem = _includeSDF->GetElement("model")->GetFirstElement();
diff --git a/test/integration/model/model_with_custom_elements/model.config b/test/integration/model/model_with_custom_elements/model.config
new file mode 100644
index 000000000..f374803a5
--- /dev/null
+++ b/test/integration/model/model_with_custom_elements/model.config
@@ -0,0 +1,5 @@
+
+
+ model_with_custom_elements
+ model.sdf
+
diff --git a/test/integration/model/model_with_custom_elements/model.sdf b/test/integration/model/model_with_custom_elements/model.sdf
new file mode 100644
index 000000000..d11a9291a
--- /dev/null
+++ b/test/integration/model/model_with_custom_elements/model.sdf
@@ -0,0 +1,22 @@
+
+
+
+
+
+
+ L1
+ L2
+
+
+
+
+
+ transmission_interface/SimpleTransmission
+
+ EffortJointInterface
+
+
+
+
+
+
diff --git a/test/integration/sdf_custom.cc b/test/integration/sdf_custom.cc
index 2b29d4f67..9f3ad54ab 100644
--- a/test/integration/sdf_custom.cc
+++ b/test/integration/sdf_custom.cc
@@ -82,3 +82,286 @@ TEST(SDFParser, CustomElements)
tranJointElement->Get("mysim:hardwareInterface");
EXPECT_EQ("EffortJointInterface", tranHwInterface);
}
+
+/////////////////////////////////////////////////
+TEST(SDFParser, ReloadCustomElements)
+{
+ const std::string sdfTestFile =
+ sdf::testing::TestFile("integration", "custom_elems_attrs.sdf");
+
+ // load file with custom elements
+ sdf::Root root1;
+ sdf::Errors errors = root1.Load(sdfTestFile);
+ EXPECT_TRUE(errors.empty());
+
+ // reload string output of root1
+ sdf::Root root2;
+ errors = root2.LoadSdfString(root1.Element()->ToString(""));
+ EXPECT_TRUE(errors.empty());
+
+ // check that root1 and root2 equal
+ const sdf::World *world1 = root1.WorldByIndex(0);
+ const sdf::World *world2 = root2.WorldByIndex(0);
+ ASSERT_NE(nullptr, world1);
+ ASSERT_NE(nullptr, world2);
+
+ const sdf::Model *model1 = world1->ModelByIndex(0);
+ const sdf::Model *model2 = world2->ModelByIndex(0);
+ ASSERT_NE(nullptr, model1);
+ ASSERT_NE(nullptr, model2);
+ EXPECT_EQ(model1->Element()->ToString(""), model2->Element()->ToString(""));
+
+ const sdf::Link *link1 = model1->LinkByIndex(0);
+ const sdf::Link *link2 = model2->LinkByIndex(0);
+ ASSERT_NE(nullptr, link1);
+ ASSERT_NE(nullptr, link2);
+ EXPECT_EQ(link1->Element()->ToString(""), link2->Element()->ToString(""));
+
+ sdf::ElementPtr customElem1 =
+ model1->Element()->FindElement("mysim:transmission");
+ sdf::ElementPtr customElem2 =
+ model2->Element()->FindElement("mysim:transmission");
+ ASSERT_NE(nullptr, customElem1);
+ ASSERT_NE(nullptr, customElem2);
+
+ const std::string customElemStr =
+R"(
+ transmission_interface/SimpleTransmission
+
+ EffortJointInterface
+
+
+)";
+ EXPECT_EQ(customElemStr, customElem1->ToString(""));
+ EXPECT_EQ(customElemStr, customElem2->ToString(""));
+
+ sdf::ElementPtr customDesc1 =
+ world1->Element()->FindElement("mysim:description");
+ sdf::ElementPtr customDesc2 =
+ world2->Element()->FindElement("mysim:description");
+ ASSERT_NE(nullptr, customDesc1);
+ ASSERT_NE(nullptr, customDesc2);
+
+ const std::string customDescStr =
+ "Description of this world\n";
+ EXPECT_EQ(customDescStr, customDesc1->ToString(""));
+ EXPECT_EQ(customDescStr, customDesc2->ToString(""));
+}
+
+/////////////////////////////////////////////////
+TEST(SDFParser, ReloadIncludedCustomElements)
+{
+ const std::string modelPath = sdf::testing::TestFile("integration", "model");
+
+ sdf::setFindCallback(
+ [&](const std::string &_file)
+ {
+ return sdf::filesystem::append(modelPath, _file);
+ });
+
+ const std::string sdfStr =
+R"(
+
+
+ model_with_custom_elements
+
+
+
+)";
+
+ // load included file with custom elements
+ sdf::Root root1;
+ sdf::Errors errors = root1.LoadSdfString(sdfStr);
+ EXPECT_TRUE(errors.empty());
+
+ // reload string output of root1
+ sdf::Root root2;
+ errors = root2.LoadSdfString(root1.Element()->ToString(""));
+ EXPECT_TRUE(errors.empty());
+
+ // check that root1 and root2 equal
+ EXPECT_EQ(root1.Element()->ToString(""), root2.Element()->ToString(""));
+
+ const sdf::World *world1 = root1.WorldByIndex(0);
+ const sdf::World *world2 = root2.WorldByIndex(0);
+ ASSERT_NE(nullptr, world1);
+ ASSERT_NE(nullptr, world2);
+
+ // //model[@name=M1]
+ const sdf::Model *model11 = world1->ModelByIndex(0);
+ const sdf::Model *model12 = world2->ModelByIndex(0);
+ ASSERT_NE(nullptr, model11);
+ ASSERT_NE(nullptr, model12);
+ EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString(""));
+
+ // //model[@name=M1]/link[@name=L1]
+ const sdf::Link *model11link1 = model11->LinkByIndex(0);
+ const sdf::Link *model12link2 = model12->LinkByIndex(0);
+ ASSERT_NE(nullptr, model11link1);
+ ASSERT_NE(nullptr, model12link2);
+
+ const std::string linkCustomAttrStr =
+ "\n";
+ EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString(""));
+ EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString(""));
+
+ // //model[@name=M1]/model[@name=M2]
+ const sdf::Model *model21 = model11->ModelByIndex(0);
+ const sdf::Model *model22 = model12->ModelByIndex(0);
+ ASSERT_NE(nullptr, model21);
+ ASSERT_NE(nullptr, model22);
+ EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString(""));
+
+ // //model[@name=M1]/model[@name=M2]/link[@name=L1]
+ const sdf::Link *model21link1 = model21->LinkByIndex(0);
+ const sdf::Link *model22link2 = model22->LinkByIndex(0);
+ ASSERT_NE(nullptr, model21link1);
+ ASSERT_NE(nullptr, model22link2);
+ EXPECT_EQ(model21link1->Element()->ToString(""),
+ model22link2->Element()->ToString(""));
+
+ // check custom attributes
+ sdf::ParamPtr param1 =
+ model21link1->Element()->GetAttribute("mysim:custom_attr_str");
+ sdf::ParamPtr param2 =
+ model22link2->Element()->GetAttribute("mysim:custom_attr_str");
+ ASSERT_NE(nullptr, param1);
+ ASSERT_NE(nullptr, param2);
+ EXPECT_EQ("B", param1->GetAsString());
+ EXPECT_EQ("B", param2->GetAsString());
+
+ // //model[@name=M1]/model[@name=M2]/link[@name=L1]/mysim:transmission
+ sdf::ElementPtr customElem1 =
+ model21link1->Element()->FindElement("mysim:transmission");
+ sdf::ElementPtr customElem2 =
+ model22link2->Element()->FindElement("mysim:transmission");
+ ASSERT_NE(nullptr, customElem1);
+ ASSERT_NE(nullptr, customElem2);
+
+ const std::string customElemStr =
+R"(
+ transmission_interface/SimpleTransmission
+
+ EffortJointInterface
+
+
+)";
+ EXPECT_EQ(customElemStr, customElem1->ToString(""));
+ EXPECT_EQ(customElemStr, customElem2->ToString(""));
+}
+
+/////////////////////////////////////////////////
+TEST(SDFParser, ReloadNestedIncludedCustomElements)
+{
+ const std::string modelPath = sdf::testing::TestFile("integration", "model");
+
+ sdf::setFindCallback(
+ [&](const std::string &_file)
+ {
+ return sdf::filesystem::append(modelPath, _file);
+ });
+
+ const std::string sdfStr =
+R"(
+
+
+
+ model_with_custom_elements
+
+
+
+
+)";
+
+ sdf::Root root1;
+ sdf::Errors errors = root1.LoadSdfString(sdfStr);
+ EXPECT_TRUE(errors.empty());
+
+ for (auto &e : errors)
+ std::cout << e.Message() << std::endl;
+
+ sdf::Root root2;
+ errors = root2.LoadSdfString(root1.Element()->ToString(""));
+ EXPECT_TRUE(errors.empty());
+
+ // check that root1 and root2 equal
+ EXPECT_EQ(root1.Element()->ToString(""), root2.Element()->ToString(""));
+
+ const sdf::World *world1 = root1.WorldByIndex(0);
+ const sdf::World *world2 = root2.WorldByIndex(0);
+ ASSERT_NE(nullptr, world1);
+ ASSERT_NE(nullptr, world2);
+
+ // //model[@name=test]
+ const sdf::Model *model11 = world1->ModelByIndex(0);
+ const sdf::Model *model12 = world2->ModelByIndex(0);
+ ASSERT_NE(nullptr, model11);
+ ASSERT_NE(nullptr, model12);
+ EXPECT_EQ(model11->Element()->ToString(""), model12->Element()->ToString(""));
+
+ // //model[@name=test]/frame[@name=M1::__model__]
+ const sdf::Frame *frame1 = model11->FrameByIndex(0);
+ const sdf::Frame *frame2 = model12->FrameByIndex(0);
+ ASSERT_NE(nullptr, frame1);
+ ASSERT_NE(nullptr, frame2);
+ EXPECT_EQ(frame1->Element()->ToString(""), frame2->Element()->ToString(""));
+
+ // //model[@name=test]/link[@name=M1::L1]
+ const sdf::Link *model11link1 = model11->LinkByIndex(0);
+ const sdf::Link *model12link2 = model12->LinkByIndex(0);
+ ASSERT_NE(nullptr, model11link1);
+ ASSERT_NE(nullptr, model12link2);
+
+ const std::string linkCustomAttrStr =
+R"(
+ 0 0 0 0 -0 0
+
+)";
+ EXPECT_EQ(linkCustomAttrStr, model11link1->Element()->ToString(""));
+ EXPECT_EQ(linkCustomAttrStr, model12link2->Element()->ToString(""));
+
+ // //model[@name=test]/model[@name=M1::M2]
+ const sdf::Model *model21 = model11->ModelByIndex(0);
+ const sdf::Model *model22 = model12->ModelByIndex(0);
+ ASSERT_NE(nullptr, model21);
+ ASSERT_NE(nullptr, model22);
+ EXPECT_EQ(model21->Element()->ToString(""), model22->Element()->ToString(""));
+
+ // //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1]
+ const sdf::Link *model21link1 = model21->LinkByIndex(0);
+ const sdf::Link *model22link2 = model22->LinkByIndex(0);
+ ASSERT_NE(nullptr, model21link1);
+ ASSERT_NE(nullptr, model22link2);
+ EXPECT_EQ(model21link1->Element()->ToString(""),
+ model22link2->Element()->ToString(""));
+
+ // check custom attributes
+ sdf::ParamPtr param1 =
+ model21link1->Element()->GetAttribute("mysim:custom_attr_str");
+ sdf::ParamPtr param2 =
+ model22link2->Element()->GetAttribute("mysim:custom_attr_str");
+ ASSERT_NE(nullptr, param1);
+ ASSERT_NE(nullptr, param2);
+ EXPECT_EQ("B", param1->GetAsString());
+ EXPECT_EQ("B", param2->GetAsString());
+
+ // //model[@name=test]/model[@name=M1::M2]/link[@name=M1::L1]
+ // /mysim:transmission
+ sdf::ElementPtr customElem1 =
+ model21link1->Element()->FindElement("mysim:transmission");
+ sdf::ElementPtr customElem2 =
+ model22link2->Element()->FindElement("mysim:transmission");
+ ASSERT_NE(nullptr, customElem1);
+ ASSERT_NE(nullptr, customElem2);
+
+ const std::string customElemStr =
+R"(
+ transmission_interface/SimpleTransmission
+
+ EffortJointInterface
+
+
+)";
+ EXPECT_EQ(customElemStr, customElem1->ToString(""));
+ EXPECT_EQ(customElemStr, customElem2->ToString(""));
+}