Hi,
we got the problem, that the rendering inside the gzserver takes long.
The scene looks like this :
The gazebo profiler shows that this takes 65 ms to render on a GTX1650 super.
Any idea of what might be going on ?
Hi,
we got the problem, that the rendering inside the gzserver takes long.
The scene looks like this :
The gazebo profiler shows that this takes 65 ms to render on a GTX1650 super.
Any idea of what might be going on ?
You seem to model like ~1.000 individual rollers:
Are these individual objects, each having their own shape and collision etc?
If so, I think that is the reason why your simulation is running slow.
In that case, I think you will need to model the box-roller-interaction in a different way (i.e. through a custom plugin) and replace the roller visuals by a texture.
There are 1530 individual rollers on this table. They are all modelled as geometry with an visual :
<link name="cell_3_2" />
<joint name="joint_cell_3_2" type="fixed">
<parent link="celluveyor" />
<child link="cell_3_2" />
<origin xyz="0.3897114471887384 0.5250000208616257 0.0" rpy="0.0 0.0 0.0" />
</joint>
<link name="wheel_u=3_v=2_wheel=0_">
<visual>
<origin xyz="0 0 -0.024000000208616257" rpy="1.5707963267948966 0 -0.0" />
<geometry>
<box size="0.04800000041723251 0.04800000041723251 0.02539999969303608" />
</geometry>
<material name="wheel_color" />
</visual>
</link>
<joint name="joint_wheel_u=3_v=2_wheel=0_" type="fixed">
<parent link="cell_3_2" />
<child link="wheel_u=3_v=2_wheel=0_" />
<origin xyz="3.061617119526112e-18 0.050000001986821495 0" rpy="0 0 0" />
<axis xyz="0 0 1" />
</joint>
<link name="wheel_u=3_v=2_wheel=1_">
<visual>
<origin xyz="0 0 -0.024000000208616257" rpy="1.5707963267948966 0 -2.0943951023931953" />
<geometry>
<box size="0.04800000041723251 0.04800000041723251 0.02539999969303608" />
</geometry>
<material name="wheel_color" />
</visual>
</link>
<joint name="joint_wheel_u=3_v=2_wheel=1_" type="fixed">
<parent link="cell_3_2" />
<child link="wheel_u=3_v=2_wheel=1_" />
<origin xyz="0.04330127190985982 -0.02500000099341074 0" rpy="0 0 0" />
<axis xyz="0 0 1" />
</joint>
<link name="wheel_u=3_v=2_wheel=2_">
<visual>
<origin xyz="0 0 -0.024000000208616257" rpy="1.5707963267948966 0 -4.1887902047863905" />
<geometry>
<box size="0.04800000041723251 0.04800000041723251 0.02539999969303608" />
</geometry>
<material name="wheel_color" />
</visual>
</link>
So in total we should render about 1530 * 8 vertices plus ~50 for the conveyors. This should not take 70 ms.
The table itself is one big collision object.
We do our physics computation ourself and only feed the resulting forces into gazebo / ODE.
Here is a picture of the gazebo profiler, that shows, that it’s really the rendering taking ages:
I do not necessarily disagree, but that does not solve your problem.
If you feel like debugging this, or if someone else comes up with a solution, then that is obviously the best option. But if not, then you need a workaround.
What I would try first is to run the same profiler test without the rollers (i.e. only table + conveyors + boxes), or with an even more empty scene (e.g. only the table), to see if that yields better results. This narrows down the cause and e.g. rules out a possible fixed delay in Camera::Render
.
And if it effectively turns out to be caused by the rollers:
If it is not:
To follow up, thank you for submitting a pull request to improve the rendering performance: Visual::SetPose performance improvement / minor fixes by jmachowinski · Pull Request #3350 · gazebosim/gazebo-classic · GitHub
Short summary from, my side :
The measurements above are already with the SetPose fix applied. I did some tests, and deactivating the rollers does indeed improve the render performance a lot.
Unifying them, as suggested by @jrtg is not straight forward, as we generate the URDF from a machine configuration on each startup of gazebo.
Assuming that we do one GL draw call per roller would make the 70ms somewhat reasonable.
Without the rollers, the render times dropped to about 10 ms for Camera::Render and ~4us per depthcamera. In the depthcamera sensor, the z-Buffer texture transfer takes about 2,3 ms.
Especially the 2.3ms for the texture transfer are a bit suspicious, to me as I would expect it to take ~75 us :
The texture should have this size :
640*480 * 32 Bit (z-buffer is float) = 9830400 Bit = 1.2MByte.
The graphics card has at least a PCIe4.0x8 connection, transfering 15.5 GByte / sec.
Therefore it should take
1.2 MByte / (15.5 * 1024 MByte / sec) = 0.0756 ms.
Is there anything wrong with my calculation ?
As even with all rollers deactivated, we can not make it to a realtime factor of 1.0. Therefore we now switched to workaround, were we inject ground truth data from gazebo into our UKF and deactivated the cameras and the vision subsystem altogether. This is sufficient for us, to test our system logic.