5

I wanted to generate datasets for perception and grasping based on the physics engine. I tried importing following 3D models released by google research recently ( https://app.ignitionrobotics.org/GoogleResearch ) into drake and creating the segmentation dataset for a variety of shoes i.e drop meshes into the bin / let it come to rest and read the rgb / depth and segmentation images.

However, specifying the object meshes (.obj files) as collision geometry in drake doesn't seem to work since the shoes just penetrate through the bin and keep falling into the abyss (attached snapshot).

enter image description here

I also noticed that YCB objects have collision geometry described using simple boxes and point contacts. Here is the visualization of the same (as you may be already familiar). Green is the collision geometry.

enter image description here

If I have to simulate the above do I need to describe simple geometry for all objects from google research dataset ? If so, how were they generated ? Are there some tools one uses to generate this or it was done manually ? or should I enable the hydroelastic contact simulation for this to work when meshes are used for collision geometry ?

If it can handle any convex mesh, an alternative is to make a convex hull of the original mesh as collision geometry.

Also as an alternative I tried the same with pybullet. Instead of the bin, I used a plane. Pybullet seems to be handling specifying the mesh as collision geometry correctly through. Here is the snapshot of the data in pybullet.

enter image description here

An intermediate solution (doesn't address the grasping part yet):

After discussion with Sean & Russ, I created convex hull of the triangle mesh (using open3D) and it appears that using this convex hull as the collision mesh and <drake:declare_convex/> annotation to mesh tag, the shoes come to stable pose. I think this solution is good enough for me for generating the perception data using drake. Here is the snapshot after using the solution below:

enter image description here

darshan
  • 1,230
  • 1
  • 11
  • 17
  • Question! How do you get the Synthetic camera Depth Data to work? Mine does not show anything! (Mask and RGB do though). And, can you get those depth values somehow? – M.K Jan 21 '22 at 09:13

1 Answers1

4

Your observations are spot on.

Drake doesn't currently support arbitrary meshes for contact (aka the "proximity" role) (only for "illustration" and "perception"). In fact, if the console is available to you, there will probably be warning printed indicating as much. Until that feature is added you have the following options:

  • As you observed in the YCB data, introduce simple primitives to approximate the meshes. Currently, there are no published techniques for generating the simple representations. It's mostly an ad hoc, by-hand approach.
  • Load an OBJ that represents a truly convex polytope and add the <drake:declare_convex> tag as the child of the <mesh> geometry. This will inform Drake to expect a convex mesh which is supported in contact. So, if you can create the convex hull easily, that might be a good direction to go.

It's difficult to recommend using hydroelastic contact. It's not quite ready for real use and has some restrictions (restrictions which may prove too problematic for you). If you're interested in investigating that further, we can explore that. But for now, I'd recommend some convex representation of your objects.

Sean Curtis
  • 1,425
  • 7
  • 8
  • 1
    Thanks Sean. Might you (and other drake-developers) add your thoughts here about why drake doesn't handle general meshes (yet), when other simulators appear to? And are there any suggestions for someone willing to contribute to the drake community to help improve the situation? (e.g. offer a script that calls a tool like meshlab to generate convex decompositions, etc?) Or perhaps we might even share a portion of the instructions that we follow when intaking new models? – Russ Tedrake Oct 04 '20 at 17:09
  • 1
    Thanks Sean and Russ. Open3D seems to have functionality to generate convex hull of an arbitrary triangle mesh. Followed your suggestion and now it seems to settle to stable pose after dropping. However, what does this mean for grasping ? I won't be able to grasp a shoe using it's collar since collision geometry won't allow it ? – darshan Oct 04 '20 at 19:34
  • 1
    FYI I believe Bullet also requires convex collision shapes (at least for moving bodies) but may be generating a convex hull for the shoes automatically. – Sherm Oct 04 '20 at 20:40
  • There are multiple challenges with general meshes. One is the question of whether they are closed manifolds or not; is there a proper "inside" and "outside"? Without that, the best you can do is define distance to the *surface* (which is strictly positive) and you can't get negative distance (inside). Computationally, even if it is properly closed, it's far more difficult to compute penetration depth for non-convex shapes (preferring a convex decomposition). There are ways to tackle these issues, Drake simply hasn't paid the price yet. – Sean Curtis Oct 05 '20 at 18:25
  • As for using convex hulls: If you have features on your mesh that disappear *inside* the hull, but it is nevertheless an important feature to interact with, you'll need to do a convex *decomposition*. Break the mesh up and create convex hulls of pieces. The minimum number of pieces that gets you the features you need. – Sean Curtis Oct 05 '20 at 18:26
  • I’ve moved this discussion to a github issue. https://github.com/RobotLocomotion/drake/issues/14197 – Russ Tedrake Oct 12 '20 at 12:29