Mesh with no faces created for small cylinders
pseudopresence opened this issue · comments
We encountered this issue when attempting to convert the Robotiq hand model from DRCSim using urdf_to_collada. If a cylinder element is smaller than 0.01, no faces are created, and urdf_to_collada will subsequently crash. From looking at the code in mesh_operations.cpp, the mesh generation for cone objects would be prone to the same issue.
The simplest fix is probably to enforce a sensible minimum for unsigned int tot
.
Here is a small example, test with rosrun collada_urdf urdf_to_collada test.urdf test.dae
.
<robot name="my_robot">
<link name="my_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder radius="0.001" length="0.5"/>
</geometry>
</collision>
</link>
</robot>
This can be closed, right?
Agreed, this issue can be closed. Some maintainers like to leave the issue open until the version with the fix is released into rosdistro.
Speaking of which, @davetcoleman etc., when can we expect a release of this package? I could do one if I was added to the ros-planning org.
I do not know, I have not been asked to do package releases, only @rethink-imcmahon and @130s. Overall ros-planning is lacking leadership IMHO
Gotcha. I'll see what I can do :)
This looks like a pretty trivial change since our last release -- pushing a new release now
released into indigo + jade in 0.4.4
thanks @mikeferguson!