How do you create a model with a programmatically generated mesh?
I would like to generate a gazebo model on the fly with a pro-grammatically created mesh. It is unclear to me how this should work. How do you specify the mesh URI for this generated mesh?
For example, lets say my program creates a plane mesh:
gazebo::common::Mesh* plane_mesh = new gazebo::common::Mesh;
gazebo::common::SubMesh* submesh = new gazebo::common::SubMesh;
submesh->AddVertex(-1,-1,0);
submesh->AddVertex(1, -1,0);
submesh->AddVertex(-1,1,0);
submesh->AddVertex(1, 1,0);
submesh->AddIndex(0);
submesh->AddIndex(1);
submesh->AddIndex(2);
submesh->AddIndex(1);
submesh->AddIndex(3);
submesh->AddIndex(2);
plane_mesh->AddSubMesh(submesh);
plane_mesh->SetName("TEST_MODEL_PLANE_MESH");
gazebo::common::MeshManager::Instance()->AddMesh(plane_mesh);
How do I refer to this mesh when I insert an SDF model? In a world plugin, what should the mesh URI for my registered plane mesh when I try to insert the model?
public: void Load(gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
{
_world->InsertModelString(R"(
<sdf version="1.4">
<model name="test_model">
<pose>0 1 2 0 0 0</pose>
<link name="link">
<gravity>false</gravity>
<static>true</static>
<visual name="visual">
<geometry>
<mesh>
<uri>TEST_MODEL_PLANE_MESH</uri>
</mesh>
</geometry>
</visual>
<collision name="collision">
<geometry>
<mesh>
<uri>TEST_MODEL_PLANE_MESH</uri>
</mesh>
</geometry>
</collision>
</link>
</model>
</sdf>
)");
Asked by adasta on 2016-08-30 21:07:01 UTC
Comments
It appears I am on the same "quest" here. Is there anyone that can explain how to refer to a programmatically inserted model/mesh. I am still looking through the Gazebo code base for answers....
Asked by Galto2000 on 2017-11-11 13:56:24 UTC
@Galto2000, any luck?
Asked by plusk01 on 2018-02-05 16:00:35 UTC
the OBJLoader in gazebo has code to construct a gazebo mesh. Maybe that'll help: https://bitbucket.org/osrf/gazebo/src/gazebo7/gazebo/common/OBJLoader.cc
Asked by iche033 on 2018-02-05 20:00:28 UTC