Gazebo camera plugin does not see some models that are in the simulation
HI!
I created a simple rock model, the visual is a .dae file and the collision is a simple box of roughly the same size. I then add multiple clones of the rock randomly distributed on the floor of my gazebo world (at the end of the world described in test2.sdf) I have a robot equipped with the Gazebo camera plugin. If I look inside the gazebo client gui, the rocks appear along all the other elements, and with the camera previzualization activated, it seems the camera sees everything (screenshot 1). But when I open for example rqt_image_view to check out the feed from the camera topic, then my rocks disappear (screenshot 2)! All the other elements are still viewed... Any idea why? And more importantly, any ideas how to fix this? I would like my robot to be able to see the rocks, for it to be able to avoid them, pick them up, etc.
Screenshot 1
Screenshot 2
Here are the files of my model
model.config
<?xml version="1.0"?>
<model>
<name>unit_box_1</name>
<version>1.0</version>
<sdf version="1.5">model.sdf</sdf>
<author>
<name>Louis M</name>
<email></email>
</author>
<description>
A Rock.
</description>
</model>
model.sdf
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="unit_box_1">
<link name="link">
<inertial>
<pose>-0.01 -0.012 0.15 0 0 0</pose>
<mass>0.390</mass>
<inertia>
<ixx>0.00058</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00058</iyy>
<iyz>0</iyz>
<izz>0.00019</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>0 0 -0.46 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.2</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
<torsional>
<coefficient>1</coefficient>
<patch_radius>0</patch_radius>
<surface_radius>0</surface_radius>
<use_patch_radius>1</use_patch_radius>
<ode>
<slip>0</slip>
</ode>
</torsional>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>1e+06</threshold>
</bounce>
<contact>
<collide_without_contact>0</collide_without_contact>
<collide_without_contact_bitmask>1</collide_without_contact_bitmask>
<collide_bitmask>1</collide_bitmask>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0</min_depth>
</ode>
<bullet>
<split_impulse>1</split_impulse>
<split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
</bullet>
</contact>
</surface>
</collision>
<visual name="visual">
<pose>0 0 -0.46 0 0 0</pose>
<geometry>
<mesh>
<uri>model://unit_box_1/meshes/experimental.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<static>0</static>
<allow_auto_disable>1</allow_auto_disable>
</model>
</sdf>
experimental.dae
<?xml version="1.0" encoding="UTF-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1">
<asset>
<contributor>
<author>VCGLab</author>
<authoring_tool>VCGLib | MeshLab</authoring_tool>
</contributor>
<up_axis>Y_UP</up_axis>
<created>Wed Apr 25 01:36:10 2012</created>
<modified>Wed Apr 25 01:36:10 2012</modified>
<unit meter="0.00254" name="inches"/>
</asset>
<library_images>
<image id="texture0" name="texture0">
<init_from>../materials/textures/coke_can.png</init_from>
</image>
</library_images>
<library_materials>
<material id ...