eleramp / pybullet-object-models

Collection of object models compatible with pybullet simulator https://github.com/bulletphysics/bullet3/tree/master/examples/pybullet
GNU Lesser General Public License v2.1
91 stars 26 forks source link

How to prepare ycb object's files? #2

Closed yuchen-x closed 3 years ago

yuchen-x commented 4 years ago

Hi,

This repo is awesome! Thank you for sharing! I'd like to have more ycb objects in pybullet, like the Lego and sugar box. Could you please let me know the details about how to reorient each object and generate the .urdf file in the end?

Thanks!

eleramp commented 3 years ago

Hi @yuchen-x, sorry for coming into this so late. Thank you for your appreciation!!

In general, you don't need to reorient the object in order to use it in pybullet. You can specify the initial pose of the object when you load the urdf with pybullet. However, if you notice some weird offsets in the object pose, you may need to reorient the object mesh. In this case, you can do it manually by using a 3D modeling software like PyMesh or Blender 3D. In my case, I had to reorient some YCB object meshes in order to match the poses defined in the GRASPA benchmark.

As concern the .urdf file, I list you the steps necessary to create a good YCB object model:

  1. Create a folder in pybullet_object_models/ycb_objects with the target name for your object.

  2. Download the YCB object mesh, either from YCB Video (better quality but not complete with all ycb objects) or from YCB Benchmark. The important files you need are:

    1. The textured mesh textured.obj
    2. The material textured.mtl
    3. The texture texture_map.png/ textured.png
  3. Create the collision mesh files as collision.obj and collision.mtl. You have 3 options:

    1. [Simpler] Use the original textured mesh as a collision mesh as well. However, collision detection is not optimized in this case.

    2. Create a convex decomposition of the original textured mesh using Hierarchical Approximate Convex Decomposition (v-HACD) decomposition in order to remove any concavity (if any). You can use this tool for Blender 3D. Also, you may need to reduce the number of vertices, by using for example the mesh decimator modifier of Blender 3D.

    1. [Better] If possible, use a primitive collision shape such as box, sphere, cylinder, to approximate the object shape of the original textured mesh. You can create it with Blender 3D.
  4. Place the files at point 2. and 3. inside the folder created at point 1.

  5. For best results, you need to compute the inertial data of your object. Specifically you need:

    1. mass: it is specified in the ycb benchmark paper
    2. center of mass: you can compute it with PyMesh or Blender
    3. inertial tensor: again you can compute it with PyMesh or Blender. Otherwise, you can use the default value [xx:1e-3, yy:1e-3, zz:1e-3]
  6. Create the model.urdf file as the following. [Change the inertial values inside the inertial tag with the ones computed at point 5.] :

    <robot name="model.urdf">
      <link name="baseLink">
        <contact>
          <lateral_friction value="0.8"/>
          <rolling_friction value="0.001"/>
          <spinning_friction value="0.001"/>
        </contact>
        <inertial>
           <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
           <mass value="0.1"/>
           <inertia ixx="1e-3" ixy="0" ixz="0" iyy="1e-3" iyz="0" izz="1e-3"/>
        </inertial>
        <visual>
          <geometry>
            <mesh filename="textured.obj" scale="1 1 1"/>
          </geometry>
          <material name="white">
            <color rgba="1. 1. 1. 1."/>
          </material>
        </visual>
        <collision>
          <geometry>
                <mesh filename="collision.obj" scale="1 1 1"/>
          </geometry>
        </collision>
      </link>
    </robot>

    You may also need to tune the friction values inside the <contact> tag.

RKJenamani commented 3 years ago

Hey @eleramp

I followed the steps you mentioned above. However, I get weird simulations in PyBullet when I load in 16k laser scan models from the YCB Object Dataset. When I drag an object to a face down position (using my cursor), it pops back to its upright position.

Alt Text

This problem persists even when using v-HACD decomposition of the original meshes as collision meshes. Is this due to a problem in the textured.obj file?

I do not face this problem with models taken from the YCB Video Dataset which uses "textured_simple.obj" (perhaps a simplification of "textured.obj" available in the former?). I tried simplifying the "textured.obj" myself, but the weird simulations persisted. However, the textured_simple_reoriented.obj files in your repository work great (no weird simulations). Can you please help me generate textured_simple_reoriented.obj from textured.obj or send the script for the same? Thanks!

eleramp commented 3 years ago

Hi @RKJenamani,

I think your problem is related to the position of the COM, which is likely positioned at the bottom of the object. You can visualize it in pybullet by doing:

obj_id = p.loadURDF("path/to/your/YcbSugarBox/model.urdf")
p.addUserDebugLine([0, 0, 0], [0.1, 0, 0], [1, 0, 0], parentObjectUniqueId=obj_id)
p.addUserDebugLine([0, 0, 0], [0, 0.1, 0], [0, 1, 0], parentObjectUniqueId=obj_id)
p.addUserDebugLine([0, 0, 0], [0, 0, 0.1], [0, 0, 1], parentObjectUniqueId=obj_id)

Did you follow step 5 of my previous instruction and then replaced the value of the computed COM in the following origin tag of the urdf model?

<inertial>
       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
RKJenamani commented 3 years ago

Hi @eleramp,

Thanks for the help! Position of centre of mass was indeed the problem. It is working correctly now! :star_struck: