Closed mjm522 closed 3 years ago
There are a few ways: if the concave part is not a rigid body, but static, use this flag to collide against the triangle mesh:
<collision concave="yes">
Alternative, if you need the concave part moving too, create a convex decomposition, and insert each part as a separate object in the obj file. You can use V-HACD to create a convex decomposition. Bullet comes with a VHACD tool that creates a convex decomposition from a Wavefront .obj file, and exports it to a new .obj file with convex parts that are automatically recognized in Bullet/PyBullet. Use premake to build the tool called test_vhacd.
I am currently working on adding signed distance fields in Bullet, see btSdfCollisionShape it will be exposed in URDF too. You can use DiscreGrid to generate the SDF. I'll report back when this is available.
thanks a lot for the reply. I am trying the methods you suggested.
A quick update, I found this python library trimesh to be extremely useful. If the v-hacd library is already installed, then update the environment variable PATH to the testVHACD executable. Once that is done,
import trimesh
from trimesh.io.urdf import export_urdf
mesh = trimesh.load(<path to STL/ OBJ/PLY file>)
export_urdf(mesh, <folder path to which urdf has to be saved>)
This will do a hierarchial decomposition of the concave object and generate a urdf file from the same. This urdf file can be easily used in bullet.
I am on Ubuntu and hence I compiled the v-hacd. My export path is as follows:
export PATH=$PATH:' <path to v-hacd>/build/linux2/test
Note: The v-hacd have the binary for OSx and Windows, for Linux it has to be compiled using the the run.py in the scripts folder and then running make in the build directory. The build directory will be automatically created upon successful running of run.py
Hi,
I am making a setup for a robot peg-insertion problem. A wide hole is constructed for both the visual shape and the collision shape. (specified by an STL file). But when the robot tries to penetrate the hole, the collision checking prevents it from insertion (can be seen here - https://youtu.be/ku-9KGcH_PQ). From the simulation, I understand that the collision shape taken is bounding the entire box instead of taking the STL file. How to prevent this?
my urdf description:
Can't this sort of setup cannot be made in bullet? If so how to specify the collision information as required? Could anyone please help? Thanks alot for your time.
Best, Michael