diff --git a/include/gz/sim/components/Model.hh b/include/gz/sim/components/Model.hh
index 3889790338..f784553cdd 100644
--- a/include/gz/sim/components/Model.hh
+++ b/include/gz/sim/components/Model.hh
@@ -41,52 +41,17 @@ namespace serializers
/// \param[in] _time Model to stream
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
- const sdf::Model &_model)
+ const sdf::Model &)
{
- sdf::ElementPtr modelElem = _model.Element();
- if (!modelElem)
- {
- gzwarn << "Unable to serialize sdf::Model" << std::endl;
- return _out;
- }
-
- bool skip = false;
- if (modelElem->HasElement("pose"))
- {
- sdf::ElementPtr poseElem = modelElem->GetElement("pose");
- if (poseElem->GetAttribute("relative_to")->GetSet())
- {
- // Skip serializing models with //pose/@relative_to attribute
- // since deserialization will fail. This could be a nested model.
- // see https://github.com/gazebosim/gz-sim/issues/1071
- // Once https://github.com/gazebosim/sdformat/issues/820 is
- // resolved, there should be an API that returns sdf::Errors objects
- // instead of printing console msgs so it would be easier to ignore
- // specific errors in Deserialize.
- static bool warned = false;
- if (!warned)
- {
- gzwarn << "Skipping serialization / deserialization for models "
- << "with //pose/@relative_to attribute."
- << std::endl;
- warned = true;
- }
- skip = true;
- }
- }
-
- if (!skip)
- {
- _out << ""
- << ""
- << modelElem->ToString("")
- << "";
-
- }
- else
- {
- _out << "";
- }
+ // Skip serialization of model sdf
+ // \todo(iche033) It was found that deserialization is
+ // very expensive, which impacts initial load time of a world with many
+ // entities. Currently only the server consumes ModelSdf components
+ // so let's skip serialization until either the deserialization
+ // performance is improved or when the GUI needs the to use Model SDF
+ // components.
+ // see, https://github.com/gazebosim/sdformat/issues/1478
+ _out << "";
return _out;
}
@@ -95,24 +60,11 @@ namespace serializers
/// \param[out] _model Model to populate
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
- sdf::Model &_model)
+ sdf::Model &)
{
- std::string sdf(std::istreambuf_iterator(_in), {});
- if (sdf.empty())
- {
- return _in;
- }
-
- // Its super expensive to create an SDFElement for some reason
- sdf::Root root;
- sdf::Errors errors = root.LoadSdfString(sdf);
- if (!root.Model())
- {
- gzwarn << "Unable to deserialize sdf::Model " << sdf<< std::endl;
- return _in;
- }
-
- _model = *root.Model();
+ // Its super expensive to create an SDFElement for some reason.
+ // So seriazliation / deserialization of model sdf is skipped
+ // https://github.com/gazebosim/sdformat/issues/1478
return _in;
}
};
diff --git a/test/integration/components.cc b/test/integration/components.cc
index 37e75f4bbf..c96bd9a625 100644
--- a/test/integration/components.cc
+++ b/test/integration/components.cc
@@ -1276,8 +1276,10 @@ TEST_F(ComponentsTest, ModelSdf)
std::istringstream istr(ostr.str());
comp2.Deserialize(istr);
- EXPECT_EQ("my_model", comp2.Data().Name());
- EXPECT_EQ(1u, comp2.Data().LinkCount());
+ // Model sdf serialization / deserialization is disabled due to perf issue
+ // https://github.com/gazebosim/sdformat/issues/1478
+ // EXPECT_EQ("my_model", comp2.Data().Name());
+ // EXPECT_EQ(1u, comp2.Data().LinkCount());
}
/////////////////////////////////////////////////