Gazebo/RViz : Emulated camera can't display STL imported object in RViz
Hello everyone, I am working on a mobile robot and wanted to simulated it in an environement in Gazebo. When I emulate a camera in gazebo and want to display it in RViz, it only shows certain objects : those that are walls or imported from the gazebo models librarie. All the objects I imported from an stl file with a .sdf (I also tried with types .dae and .obj) do display in gazebo but don't show in the RVIZ display (topic: /3Dcamera/color/image_raw with camera or image displays). Here is the example of the model.sdf that I can display on gazebo but not RViZ: C:\fakepath\model.sdf
Here is the difference in RViz between the box I want displayed and a wheel from a gazebo librarie in front of a wall created with Building Editor in Gazebo: in gazebo:
in RViz:
In the environnement I load, the lines for this particular box is shown below (it's the same principle for every imported stl object):
</model>
<model name='boites_clone_0'>
<pose>-5.62328 -0.573398 0.4 0 -0 1.3e-05</pose>
<link name='stl_test_box'>
<collision name='Wall_4_Collision'>
<geometry>
<box>
<size>0.82 0.85 0.4</size>
</box>
</geometry>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode/>
</contact>
<bounce/>
<friction>
<torsional>
<ode/>
</torsional>
<ode/>
</friction>
</surface>
</collision>
<visual name='Wall_4_Visual'>
<pose>-0.05 0.1 -0.3 0 -0 0</pose>
<geometry>
<mesh>
<uri>model://world/meshes/bloc-carton.stl</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/DarkYellow</name>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
<static>1</static>
</model>
I'm using Gazebo 11.9.0 and ROS Noetic on Ubunto 20.04. The STL models come from a mechanical simulation generated inFreeCad. If anyone of you has an ideas or answers to this issue, i'd be pleased to hear them. Thank you.
Asked by thomzem on 2022-03-14 11:44:00 UTC
Answers
I was having a similar problem with various models I've downloaded, where they would show up in Gazebo but not in RViz. In my case, I found that Gazebo was not searching in the correct places for the materials and meshes, and found the answer from this post on how to add your model directory to the package.xml file.
https://answers.gazebosim.org//question/16159/how-to-include-uri-relatively/
I hope this helps!
Asked by rialia on 2023-03-23 08:55:03 UTC
Comments