Skip to content

Allow loading a model SDF file in the Server class #1775

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 16 commits into from
Nov 9, 2022
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -192,6 +192,13 @@ gz_build_tests(TYPE UNIT
gz-sim${PROJECT_VERSION_MAJOR}
)

# Server unit tests require rendering.
if (TARGET UNIT_Server_TEST)
target_link_libraries(UNIT_Server_TEST
gz-rendering${GZ_RENDERING_VER}::gz-rendering${GZ_RENDERING_VER}
)
endif()

# Command line tests need extra settings
foreach(CMD_TEST
UNIT_gz_TEST
Expand Down
21 changes: 20 additions & 1 deletion src/Server.cc
Original file line number Diff line number Diff line change
Expand Up @@ -113,12 +113,31 @@ Server::Server(const ServerConfig &_config)

gzmsg << "Loading SDF world file[" << filePath << "].\n";

sdf::Root sdfRoot = sdf::Root();
// \todo(nkoenig) Async resource download.
// This call can block for a long period of time while
// resources are downloaded. Blocking here causes the GUI to block with
// a black screen (search for "Async resource download" in
// 'src/gui_main.cc'.
errors = this->dataPtr->sdfRoot.Load(filePath);
errors = sdfRoot.Load(filePath);
if (errors.empty()) {
if (sdfRoot.Model() == nullptr) {
this->dataPtr->sdfRoot = std::move(sdfRoot);
}
else
{
// If the specified file only contains a model, load the default
// world and add the model to it.
const sdf::Model model = *(sdfRoot.Model());
errors = this->dataPtr->sdfRoot.LoadSdfString(DefaultWorld::World());
assert(this->dataPtr->sdfRoot.WorldCount() == 1);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think we use assert in our code base very much, so this seems out of place, but I'm not opposed to using it.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, I was worndering about that. The other options that come to mind would be to catch this via if statement, or leave this uncaught. I have no strong preference, I'll go with whatever you-all think is best.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think it would be sufficient to add an if statement and returning early if world is nullptr.

sdf::World *world = this->dataPtr->sdfRoot.WorldByIndex(0);
assert(world->AddModel(model));
if (errors.empty()) {
errors = this->dataPtr->sdfRoot.UpdateGraphs();
}
}
}
break;
}

Expand Down
169 changes: 169 additions & 0 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,10 @@
#include <gz/common/StringUtils.hh>
#include <gz/common/Util.hh>
#include <gz/math/Rand.hh>
#include <gz/rendering/RenderEngine.hh>
#include <gz/rendering/RenderingIface.hh>
#include <gz/rendering/Scene.hh>
#include <gz/sim/rendering/Events.hh>
#include <gz/transport/Node.hh>
#include <gz/utils/ExtraTestMacros.hh>
#include <sdf/Mesh.hh>
Expand Down Expand Up @@ -519,6 +523,171 @@ TEST_P(ServerFixture, SdfStringServerConfig)
EXPECT_EQ(2u, *server.SystemCount());
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, LoadSdfModel)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can this be removed or be added to the other file? We need to reduce the number of tests in Server_TEST.cc.

Copy link
Contributor Author

@JoanAguilar JoanAguilar Nov 4, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fine with me. This test will then be in Server_Rendering_TEST.cc and not require rendering, but I understand we are OK with that. (Or I guess I could just remove it.)

{
gz::sim::ServerConfig serverConfig;

serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH,
"test", "worlds", "models", "sphere", "model.sdf"));

sim::Server server = Server(serverConfig);
EXPECT_TRUE(server.HasEntity("sphere"));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, LoadSdfModelRelativeUri)
{

class CheckMeshPlugin:
public System,
public gz::sim::ISystemConfigure,
public gz::sim::ISystemPreUpdate
{
private: common::ConnectionPtr connection{nullptr};

private: rendering::ScenePtr scene{nullptr};

private: EventManager *eventMgr{nullptr};

bool FindScene()
{
auto loadedEngNames = gz::rendering::loadedEngines();
if (loadedEngNames.empty())
{
gzdbg << "No rendering engine is loaded yet" << std::endl;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This works, but I think the recommended way to return a failure with a reason is for the function to return an AssertionResult (http://google.github.io/googletest/advanced.html#using-a-function-that-returns-an-assertionresult)

return false;
}

// assume there is only one engine loaded
auto engineName = loadedEngNames[0];
if (loadedEngNames.size() > 1)
{
gzdbg << "More than one engine is available. "
<< "Using engine [" << engineName << "]" << std::endl;
return false;
}
auto engine = gz::rendering::engine(engineName);
if (!engine)
{
gzerr << "Internal error: failed to load engine [" << engineName
<< "]. Grid plugin won't work." << std::endl;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is the grid plugin relevant here?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No. FWIW, I took this from RenderingGuiPlugin::FindScene. I'll update this.

return false;
}

if (engine->SceneCount() == 0)
{
gzdbg << "No scene has been created yet" << std::endl;
return false;
}

// Get first scene
auto scenePtr = engine->SceneByIndex(0);
if (nullptr == scenePtr)
{
gzerr << "Internal error: scene is null." << std::endl;
return false;
}

if (engine->SceneCount() > 1)
{
gzdbg << "More than one scene is available. "
<< "Using scene [" << scene->Name() << "]" << std::endl;
}

if (!scenePtr->IsInitialized() || nullptr == scenePtr->RootVisual())
{
return false;
}

this->scene = scenePtr;
return true;
};

private: void CheckMeshes(){
if (this->scene == nullptr){
ASSERT_TRUE(this->FindScene());
}
ASSERT_TRUE(this->scene != nullptr);
ASSERT_TRUE(this->scene->IsInitialized());

std::shared_ptr<rendering::Visual> v1 = this->scene->VisualByName(
"relative_resource_uri::L1::V1"
);
// There's only one geometry under this visual, which has to be the mesh.
EXPECT_EQ(v1->GeometryCount(), 1);
std::shared_ptr<rendering::Geometry> v1Geom = v1->GeometryByIndex(0);
// Attempt to cast the geometry into a mesh, in order to determine that
// the mesh has been properly loaded.
std::shared_ptr<rendering::Mesh> v1Mesh =
std::dynamic_pointer_cast<rendering::Mesh>(v1Geom);
EXPECT_NE(v1Mesh, nullptr);

std::shared_ptr<rendering::Visual> v2 = this->scene->VisualByName(
"relative_resource_uri::L1::V2"
);
// There should be no geometries under this visual, as the mesh file
// refers to a non-existent file, and the mesh should not be loaded.
EXPECT_EQ(v2->GeometryCount(), 0);
}

public: void Configure(
const Entity &,
const std::shared_ptr<const sdf::Element> &,
EntityComponentManager &,
EventManager &_eventMgr
)
{
// Register CheckMeshes with the PreRender event.
this->connection =
_eventMgr.Connect<events::PreRender>(
std::bind(&CheckMeshPlugin::CheckMeshes, this)
);
this->eventMgr = &_eventMgr;
};

public: void PreUpdate(const UpdateInfo &, EntityComponentManager &)
{
// Emit a ForceRender event so the PreRender event is triggered.
this->eventMgr->Emit<events::ForceRender>();
};
};

gz::sim::ServerConfig serverConfig;

serverConfig.SetSdfFile(common::joinPaths(PROJECT_SOURCE_PATH,
"test", "worlds", "models", "relative_resource_uri", "model2.sdf"));

// Add the Sensors plugin so rendering is available.
sdf::Plugin sdfSensorsPlugin = sdf::Plugin(
"gz-sim-sensors-system",
"gz::sim::systems::Sensors",
"<render_engine>ogre2</render_engine>"
);
ServerConfig::PluginInfo sensorsPluginInfo = ServerConfig::PluginInfo(
"default",
"world",
sdfSensorsPlugin
);
serverConfig.AddPlugin(sensorsPluginInfo);

sim::Server server = Server(serverConfig);
EXPECT_TRUE(server.HasEntity("relative_resource_uri"));
EXPECT_TRUE(server.HasEntity("L1"));
EXPECT_TRUE(server.HasEntity("V1"));
EXPECT_TRUE(server.HasEntity("V2"));

std::shared_ptr<CheckMeshPlugin> meshChecker =
std::make_shared<CheckMeshPlugin>();
std::optional<bool> meshCheckerAddSuccess = server.AddSystem(meshChecker);
ASSERT_TRUE(meshCheckerAddSuccess);
if (meshCheckerAddSuccess) {
ASSERT_TRUE(meshCheckerAddSuccess.value());
}
ASSERT_TRUE(server.RunOnce());
ASSERT_TRUE(server.RunOnce(false));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, RunBlocking)
{
Expand Down
108 changes: 108 additions & 0 deletions test/worlds/models/relative_resource_uri/meshes/box.dae
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0</authoring_tool>
</contributor>
<created>2015-05-26T11:01:50</created>
<modified>2015-05-26T11:01:50</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
<effect id="Material-effect">
<profile_COMMON>
<technique sid="common">
<phong>
<emission>
<color sid="emission">0.2 0.2 0.2 1</color>
</emission>
<ambient>
<color sid="ambient">0.9 0.9 0.9 1</color>
</ambient>
<specular>
<color sid="specular">0.5 0.5 0.5 1</color>
</specular>
<shininess>
<float sid="shininess">50</float>
</shininess>
<index_of_refraction>
<float sid="index_of_refraction">1</float>
</index_of_refraction>
</phong>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_materials>
<material id="Material-material" name="Material">
<instance_effect url="#Material-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="36">0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 1.78814e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 2.38419e-7</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="12" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map">
<float_array id="Cube-mesh-map-array" count="72">0.004854381 0.6715211 0.3284789 0.671521 0.3284789 0.9951456 0.9951456 0.6618123 0.6715211 0.6618123 0.6715211 0.3381878 0.00485444 0.6618123 0.004854321 0.3381878 0.3284789 0.3381878 0.004854321 0.00485444 0.3284789 0.004854321 0.3284789 0.3284789 0.9951457 0.3284789 0.6715211 0.3284789 0.6715211 0.00485444 0.6618123 0.004854381 0.6618123 0.3284788 0.3381878 0.3284789 0.004854321 0.9951456 0.004854381 0.6715211 0.3284789 0.9951456 0.9951456 0.3381877 0.9951456 0.6618123 0.6715211 0.3381878 0.3284791 0.6618123 0.00485444 0.6618123 0.3284789 0.3381878 0.004854381 0.328479 0.004854321 0.00485444 0.3284789 0.3284789 0.9951457 0.004854321 0.9951457 0.3284789 0.6715211 0.00485444 0.3381877 0.004854321 0.6618123 0.004854381 0.3381878 0.3284789</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<polylist material="Material-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map" offset="2" set="0"/>
<vcount>3 3 3 3 3 3 3 3 3 3 3 3 </vcount>
<p>0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35</p>
</polylist>
</mesh>
</geometry>
</library_geometries>
<library_controllers/>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Cube" name="Cube" type="NODE">
<matrix sid="transform">0.3999998 0 0 0 0 0.4 0 0 0 0 0.4 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh">
<bind_material>
<technique_common>
<instance_material symbol="Material-material" target="#Material-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>
27 changes: 27 additions & 0 deletions test/worlds/models/relative_resource_uri/model2.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
<?xml version='1.0'?>

<!-- Note that some of the meshes don't exist. -->

<sdf version='1.6'>
<model name='relative_resource_uri'>
<pose>0 0 1 0 0 0</pose>
<link name='L1'>
<visual name='V1'>
<geometry>
<mesh>
<uri>meshes/box.dae</uri>
</mesh>
</geometry>
</visual>
<visual name='V2'>
<pose>1 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>meshes/nonexistent.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>