Skip to content

MeshManager returns nullptr when asked for ignition::common::Mesh* in function MeshByName if mesh name is a url #1796

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

Closed
Jakub-Krakowiak opened this issue Nov 14, 2022 · 4 comments
Assignees
Labels
bug Something isn't working

Comments

@Jakub-Krakowiak
Copy link

Environment

  • OS Version: Ubuntu 20.04
  • Source or binary build? binary fortress 6.12
    - [x] running on a dual GPU machine (integrated GPU + discrete GPU)
    - [ ] running on a multi-GPU machine (it has multiple discrete GPUs)
    - [x] running on real hardware
    - [ ] running in virtual machine
    - [ ] running in Docker/Singularity
    - [ ] running remotely (e.g. via SSH)
    - [ ] running in a cloud
    - [ ] using VirtualGL, XVFB, Xdummy, XVNC or other indirect rendering utilities
    - [x] GPU is concurrently used for other tasks
    - [x] desktop acceleration
    - [ ] video decoding (i.e. a playing Youtube video)
    - [ ] video encoding
    - [x] CUDA/ROCm computations (Tensorflow, Torch, Caffe running)
    - [ ] multiple simulators running at the same time
    - [ ] other...
    • Rendering system info:
    • Nvidia GTX 2070 Super (laptop version)
    • X.Org X Server 1.20.13
      X Protocol Version 11, Revision 0
I am currently working on implementing a Lidar gazebo server plugin using NVIDIA Optix. To get mesh info from Gazebo sim I am using the MeshManager class, querying mesh by name. I am not able to get an accurate pointer when querying names of newly added meshes from sdf, because of a desinchronization of EntityComponentManager and MeshManager.

Description

  • Expected behavior: the MeshManager is able to return accurate pointers to meshes when queried by name that is a url.

  • Actual behavior: the MeshManager returns nullptr when queried by name that is a url, despite the fact, that 10 sim updates later it gives a valid result for the same name.

Steps to reproduce

  1. Implement a standard system plugin (e. g. using your tutorial)
  2. implement Configure function:
void RGLServerPluginManager::Configure(
        const ignition::gazebo::Entity& entity,
        const std::shared_ptr<const sdf::Element>&,
        ignition::gazebo::EntityComponentManager& ecm,
        ignition::gazebo::EventManager& evm) {

    ecm.Each<ignition::gazebo::components::Visual, ignition::gazebo::components::Geometry>
            (std::bind(&RGLServerPluginManager::LoadEntityToRGLCb, this, _1, _2, _3));
}

bool RGLServerPluginManager::LoadEntityToRGLCb(
        const ignition::gazebo::Entity& entity,
        const ignition::gazebo::components::Visual*,
        const ignition::gazebo::components::Geometry* geometry) {
    rgl_mesh_t new_mesh;
    if (!LoadMeshToRGL(&new_mesh, geometry->Data())) {
        return true;
    }
}

bool RGLServerPluginManager::LoadMeshToRGL(
        rgl_mesh_t* new_mesh,
        const sdf::Geometry& data) {

    double scale_x = 1;
    double scale_y = 1;
    double scale_z = 1;

    auto mesh_common = GetMeshPointer(data, scale_x, scale_y, scale_z);
	return true;
}

const ignition::common::Mesh* RGLServerPluginManager::GetMeshPointer(
        const sdf::Geometry& data,
        double& scale_x,
        double& scale_y,
        double& scale_z) {

    const ignition::common::Mesh* mesh_pointer;

    if (data.Type() == sdf::GeometryType::MESH) {
            mesh_pointer = LoadMesh(data, scale_x, scale_y, scale_z);
	if (nullptr == mesh_pointer && data.Type() == sdf::GeometryType::MESH) {
        ignerr << "Error in importing mesh named: " << ignition::gazebo::asFullPath(
                data.MeshShape()->Uri(),
                data.MeshShape()->FilePath())  <<  " it will not be loaded to RGL\n";
    } else if (data.Type() == sdf::GeometryType::MESH) {
        ignerr << "Imported mesh named: " << ignition::gazebo::asFullPath(
                data.MeshShape()->Uri(),
                data.MeshShape()->FilePath()) << " \n";
    	}
	}
    return mesh_pointer;
}

const ignition::common::Mesh* RGLServerPluginManager::LoadMesh(
        const sdf::Geometry& data,
        double& scale_x,
        double& scale_y,
        double& scale_z) {

    auto scale = data.MeshShape()->Scale();

    scale_x = scale.X();
    scale_y = scale.Y();
    scale_z = scale.Z();

    return mesh_manager->MeshByName(ignition::gazebo::asFullPath(
            data.MeshShape()->Uri(),
            data.MeshShape()->FilePath()));
}

  1. run a world with this plugin active and a mesh geometry in .sdf file

Output


// At Configure() time:

[Err] [Mesh.cc:200] Imported mesh named: /home/jakub/CLionProjects/RGLGazeboPlugin/test_world/meshes/minecartengine.dae 
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/body.dae it will not be loaded to RGL
[Err] [Mesh.cc:200] Imported mesh named: /home/jakub/.ignition/fuel/fuel.gazebosim.org/elene/models/bosdyn_spot/1/meshes/spot_payload.stl 
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_left_hip.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_left_upper_leg.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_left_lower_leg.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_right_hip.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_right_upper_leg.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_right_lower_leg.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_left_hip.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_left_upper_leg.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_left_lower_leg.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_right_hip.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_right_upper_leg.dae it will not be loaded to RGL
[Err] [Mesh.cc:196] Error in importing mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_right_lower_leg.dae it will not be loaded to RGL

// After 10 simuation updates:

[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/body.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_left_hip.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_left_upper_leg.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_left_lower_leg.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_right_hip.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_right_upper_leg.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/front_right_lower_leg.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_left_hip.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_left_upper_leg.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_left_lower_leg.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_right_hip.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_right_upper_leg.dae 
[Err] [Mesh.cc:200] Imported mesh named: https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/BOSDYN_SPOT/tip/files/meshes/rear_right_lower_leg.dae 

@Jakub-Krakowiak Jakub-Krakowiak added the bug Something isn't working label Nov 14, 2022
@azeey azeey self-assigned this Nov 14, 2022
@azeey
Copy link
Contributor

azeey commented Nov 14, 2022

Thanks for the detailed issue @Jakub-Krakowiak. However, would you be able to provide more detail as to how you're running the simulation? Is the model loaded from an sdf world file or spawned during runtime? Also, Configure is meant to be called just once when the system is loaded. How is it that it's still running after 10 updates? Does the error happen every time you run your test or only the first time when the mesh is downloaded from Fuel?

@Jakub-Krakowiak
Copy link
Author

Jakub-Krakowiak commented Nov 15, 2022

The model is loaded from an sdf file:

<include>
      <uri>
      		https://fuel.gazebosim.org/1.0/Elene/models/bosdyn_spot
      </uri>
</include>

The model meshes are not available every time I run the world, even when the files themselves are already downloaded and located in the .ignition folder in $HOME directory. I will be testing adding a model from fuel (both dowloaded and not downloaded) in runtime today, so I will add the info here.

I am also implementing the PostUpdate System Plugin Interface, so I manually count the number of times the PostUpdate function is called (because info.iterations does not increase while simulation is paused (possibly connected to my other issue)) and at the 10'th time I do another ecm.Each.


void RGLServerPluginManager::PostUpdate(
        const ignition::gazebo::UpdateInfo& info,
        const ignition::gazebo::EntityComponentManager& ecm) {

    current_update++;

    if (current_update == 10) {
        ecm.Each<ignition::gazebo::components::Visual, ignition::gazebo::components::Geometry>
            (std::bind(&RGLServerPluginManager::LoadEntityToRGLCb, this, _1, _2, _3));
    } else {
        ecm.EachNew<ignition::gazebo::components::Visual, ignition::gazebo::components::Geometry>
                (std::bind(&RGLServerPluginManager::LoadEntityToRGLCb, this, _1, _2, _3));
    }
}

I have been running the world with "ign gazebo world.sdf" command so it was paused at start. I will also try running it with -r option and see if it changes anything. (Edit: it still cant get mesh when the entitiy is created, but can 10 updates later)

@azeey
Copy link
Contributor

azeey commented Nov 28, 2022

I was able to run your system locally and see the error your reported. However, I don't believe this is a bug in Gazebo, so I'll go ahead and close this ticket. Here's my explanation and suggestion for what you could do:

The MeshManager does not have all the meshes at the beginning of simulation. Meshes are added to it as various systems load their meshes at different times. On the server side, the .dae files are only loaded by the Sensors system. The Physics system loads only the meshes in the <collision> tag, but the .dae files in your examples are used by <visual> meshes. The Sensors system runs at a frequency that is determined by the sensors in your world, so in your case, it ran at the 10th step.

The best thing to do is to call MeshManager::Load instead of MeshByName since Load will only load the mesh from disk if it hasn't already been loaded.

@azeey azeey closed this as not planned Won't fix, can't repro, duplicate, stale Nov 28, 2022
@Jakub-Krakowiak
Copy link
Author

Thank you for your suggestion to use the MeshManager::Load function. The plugin now works as intended.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
Archived in project
Development

No branches or pull requests

2 participants