Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

pybullet: unwanted convex hull collision check for obj-file with convex objects inside #1507

Closed
airballking opened this issue Jan 12, 2018 · 7 comments

Comments

@airballking
Copy link

Dear Bullet developers,

I want to have collision checking for a concave mesh (a mug) in pybullet. Following a hint from the documentation, I created a convex decomposition using the tool v-hacd and saved the result as an obj-file. The decomposed mesh looks fine in Blender. However, when I load the mesh through a simple URDF in Bullet, it seems that there still a convex hull is used for the object.

Mesh in Blender:
mug_blender

Mesh in Bulllet:
mug_pybullet

My questions:

  1. Does Pybullet support collision checking for meshes with openings like my convex decomposition of the mug?
  2. If yes, could you point me to an example that show-cases this behavior?
  3. Also, are there some known pitfalls when using v-hacd to prepare obj-files for Pybullet?

Thank you for your support! Best,
Georg.

P.S.: Here is a small ROS package with the meshes and a dummy application playthings.py that you can use to load my obj-mesh in Bullet:
my_pkg.zip

@erwincoumans
Copy link
Member

erwincoumans commented Jan 12, 2018

Your VHACD obj still contains the original cup, just remove it and it should work fine. Attached is your fixed cup.obj zipped.
mug.zip
cup.zip

Instead of using Blender, you can compile the Bullet SDK using premake and there is an executable that creates VHACD from obj to obj called Bullet/bin/test_vhacd_gmake_x64_release.

Various VHACD examples are in Bullet/data for example duck_vhacd.obj

image

I just added another cup, this one has a separate visual mesh, so it looks nicer:
https://github.com/bulletphysics/bullet3/tree/master/data/dinnerware/cup

Note that PyBullet will search relative to a data folder around your current working directory. Meshes and other assets will be searched relative to the URDF file, so a relative path works well.
For the URDF file, you can use PyBullet.setAdditionalSearchPath to add another asset root (used to resolve URDF file names)

@airballking
Copy link
Author

Thank you very much for the quick and very helpful response. I was not aware that I had to remove the old mesh. I thought VHACD would just replace it.

Also, thanks for adding a cup to your database. That is very nice and helpful.

I consider my question answered. Hence, I close this issue.

@a-z-e-r-i-l-a
Copy link

a-z-e-r-i-l-a commented Jan 30, 2020

Instead of using Blender, you can compile the Bullet SDK using premake and there is an executable that creates VHACD from obj to obj called Bullet/bin/test_vhacd_gmake_x64_release.

@erwincoumans Hi, can you please tell a bit more how we can do this? I'm not sure what I should download or what command to use. Does it also work on stl files or only files with .obj format.

Thanks

@erwincoumans
Copy link
Member

erwincoumans commented Mar 16, 2020

@a-z-e-r-i-l-a PyBullet 2.6.7 onwards comes with vhacd included. Check the PyBullet Quickstart Guide for usage/paramaters.

pip3 install pybullet --upgrade --user

#now in a script you can use

import pybullet as p
import pybullet_data as pd
import os

p.connect(p.DIRECT)
name_in = os.path.join(pd.getDataPath(), "duck.obj")
name_out = "duck_vhacd2.obj"
name_log = "log.txt"
p.vhacd(name_in, name_out, name_log, alpha=0.04,resolution=50000 )

@anandbhattad
Copy link

Hi, how do I save the convex mesh from the command line?

@erwincoumans
Copy link
Member

See attached file how to use vhacd in pybullet:
vhacd_pybullet.zip

@francogassibe
Copy link

Hi there, i use the v-hacd tool and in general i have no problems, but recently i had problems with some meshes.
Do someone know what requirements does my mesh needs to have?
Im thinking about things like:

  • if its a closed mesh
  • the size of the mesh (if its too heavy)
  • connectivity

The error i get is just "b3Printf: Request createCollisionShape failed"

My .stl files come from a Solid Works assembled project so i think that there might be some screws or litle parts inside my main part that may cause problems.

Here is one of my STLs my_piece.zip
Thank you in advance

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

5 participants