yunshengtian/Assemble-Them-All

Request of the guidance of the proper XML simulation setting for NIST gear meshing

lenardxu opened this issue · 8 comments

Hi, @yunshengtian. First thank you for your great share on the assembly plan.

I am now using your implementation for the assembly plan on the example of gear meshing in the NIST challenge (https://www.nist.gov/el/intelligent-systems-division-73500/robotic-grasping-and-manipulation-assembly/assembly). In this specific example, I want to generate the disassembly plan for the gears under the simultaneous effect of both translational force and torque (in the same direction). The gear assembly looks as below.
nist_gear_assembled_state

However, when I changed the XML simulation settings correspondingly to make the disassembly process work based on your defined physics model, weird things happen. As you can see in the gifs below, (the 1st gif) the medium-sized and small-sized gears don't revolute around their respective axis, or at least move in a physically expected way. Instead, they keep still with severe mesh penetration between the large and medium gears. Similarly, (the 2nd gif) the small-sized gear moves in an anomaly way along with severe mesh penetration.

0_2
1_1

And here are the corresponding XML strings for both gifs.
For the 1st gif, 'part2' refers to the large gear, 'part0' the small one, 'part1' the medium one, and 'part3' the base holding the gears.

<redmax model="assemble">
<option integrator="BDF1" timestep="1e-3" gravity="0. 0. 1e-12"/>
<render bg_color="255 255 255 255"/>

<default>
    <general_SDF_contact kn="1000000.0" kt="1e-12" mu="0.0" damping="0.0"/>
</default>

<robot>
    <link name="part2">
        <joint name="part2" type="free3d-exp" axis="0.0 0.0 0.0" pos="-2.459021304856198 0.002167244860656758 -0.006609842408113079" quat="1 0 0 0" frame="WORLD" damping="0.0"/>
        <body name="part2" type="SDF" filename="/home/rkx/Telekinesis/code_base/autoplan/resources/preprocessed_obj/00010/2.obj" load_sdf="true" save_sdf="true" pos="0 0 0" quat="1 0 0 0" scale="1 1 1" transform_type="OBJ_TO_JOINT" density="1" dx="0.05" col_th="0.013587286900234731" mu="0.0" rgba="0.23529411764705882 0.6549019607843137 0.8666666666666667 1.0"/>
    </link>
</robot>

<robot>
    <link name="part0">
        <joint name="part0" type="free3d-exp" axis="0.0 0.0 0.0" pos="4.098382401387394 -0.0003343830775857804 0.08086139665247331" quat="1 0 0 0" frame="WORLD" damping="0.0"/>
        <body name="part0" type="SDF" filename="/home/rkx/Telekinesis/code_base/autoplan/resources/preprocessed_obj/00010/0.obj" load_sdf="true" save_sdf="true" pos="0 0 0" quat="1 0 0 0" scale="1 1 1" transform_type="OBJ_TO_JOINT" density="1" dx="0.05" col_th="0.013587286900234731" mu="0.0" rgba="0.8235294117647058 0.3411764705882353 0.34901960784313724 1.0"/>
    </link>
</robot>

<robot>
    <link name="part1">
        <joint name="part1" type="free3d-exp" axis="0.0 0.0 0.0" pos="1.639126402467036 0.0029291938313094857 0.07973205865685809" quat="1 0 0 0" frame="WORLD" damping="0.0"/>
        <body name="part1" type="SDF" filename="/home/rkx/Telekinesis/code_base/autoplan/resources/preprocessed_obj/00010/1.obj" load_sdf="true" save_sdf="true" pos="0 0 0" quat="1 0 0 0" scale="1 1 1" transform_type="OBJ_TO_JOINT" density="1" dx="0.05" col_th="0.013587286900234731" mu="0.0" rgba="0.9294117647058824 0.8 0.28627450980392155 1.0"/>
    </link>
</robot>

<robot>
    <link name="part3">
        <joint name="part3" type="fixed" axis="0.0 0.0 0.0" pos="0.09422816528262493 7.229772216127662e-07 -0.7300483687716826" quat="1 0 0 0" frame="WORLD" damping="0.0"/>
        <body name="part3" type="SDF" filename="/home/rkx/Telekinesis/code_base/autoplan/resources/preprocessed_obj/00010/3.obj" load_sdf="true" save_sdf="true" pos="0 0 0" quat="1 0 0 0" scale="1 1 1" transform_type="OBJ_TO_JOINT" density="1" dx="0.05" col_th="0.013587286900234731" mu="0.0" rgba="0.7450980392156863 0.49411764705882355 0.8156862745098039 1.0"/>
    </link>
</robot>

<contact>

    <general_SDF_contact general_body="part2" SDF_body="part0"/>
    <general_SDF_contact general_body="part0" SDF_body="part2"/>

    <general_SDF_contact general_body="part2" SDF_body="part1"/>
    <general_SDF_contact general_body="part1" SDF_body="part2"/>

    <general_SDF_contact general_body="part2" SDF_body="part3"/>
    <general_SDF_contact general_body="part3" SDF_body="part2"/>

</contact>
</redmax>

For the 2nd gif, 'part1' refers to the medium one, 'part0' the small one, and 'part3' the base holding the gears.

<redmax model="assemble">
<option integrator="BDF1" timestep="1e-3" gravity="0. 0. 1e-12"/>
<render bg_color="255 255 255 255"/>

<default>
    <general_SDF_contact kn="1000000.0" kt="1e-12" mu="0.0" damping="0.0"/>
</default>

<robot>
    <link name="part1">
        <joint name="part1" type="free3d-exp" axis="0.0 0.0 0.0" pos="1.639126402467036 0.0029291938313094857 0.07973205865685809" quat="1 0 0 0" frame="WORLD" damping="0.0"/>
        <body name="part1" type="SDF" filename="/home/rkx/Telekinesis/code_base/autoplan/resources/preprocessed_obj/00010/1.obj" load_sdf="true" save_sdf="true" pos="0 0 0" quat="1 0 0 0" scale="1 1 1" transform_type="OBJ_TO_JOINT" density="1" dx="0.05" col_th="0.013617513774617371" mu="0.0" rgba="0.9294117647058824 0.8 0.28627450980392155 1.0"/>
    </link>
</robot>

<robot>
    <link name="part0">
        <joint name="part0" type="free3d-exp" axis="0.0 0.0 0.0" pos="4.098382401387394 -0.0003343830775857804 0.08086139665247331" quat="1 0 0 0" frame="WORLD" damping="0.0"/>
        <body name="part0" type="SDF" filename="/home/rkx/Telekinesis/code_base/autoplan/resources/preprocessed_obj/00010/0.obj" load_sdf="true" save_sdf="true" pos="0 0 0" quat="1 0 0 0" scale="1 1 1" transform_type="OBJ_TO_JOINT" density="1" dx="0.05" col_th="0.013617513774617371" mu="0.0" rgba="0.8235294117647058 0.3411764705882353 0.34901960784313724 1.0"/>
    </link>
</robot>

<robot>
    <link name="part3">
        <joint name="part3" type="fixed" axis="0.0 0.0 0.0" pos="0.09422816528262493 7.229772216127662e-07 -0.7300483687716826" quat="1 0 0 0" frame="WORLD" damping="0.0"/>
        <body name="part3" type="SDF" filename="/home/rkx/Telekinesis/code_base/autoplan/resources/preprocessed_obj/00010/3.obj" load_sdf="true" save_sdf="true" pos="0 0 0" quat="1 0 0 0" scale="1 1 1" transform_type="OBJ_TO_JOINT" density="1" dx="0.05" col_th="0.013617513774617371" mu="0.0" rgba="0.7450980392156863 0.49411764705882355 0.8156862745098039 1.0"/>
    </link>
</robot>

<contact>

    <general_SDF_contact general_body="part1" SDF_body="part0"/>
    <general_SDF_contact general_body="part0" SDF_body="part1"/>

    <general_SDF_contact general_body="part1" SDF_body="part3"/>
    <general_SDF_contact general_body="part3" SDF_body="part1"/>

</contact>
</redmax>

Many thanks for any kindly helpful support!

Have you checked Note 2 here in this section of our readme https://github.com/yunshengtian/Assemble-Them-All?tab=readme-ov-file#4-install-assembly-datasets? You'll need to make sure the mesh resolution is enough for such complex geometries with local rich geometry features, i.e., have dense vertices for accurate contact handling.

I tried with your suggestion. However, it still doesn't work according to the simulation rendering results based on a set of experiments with parameter changes below.
->
The changes of mesh resolution (via your subdivide.py) and lower limit of sdf grid size (via the command line argument) I made are summarized below.
experiments_on_autoplan_simulation

In this case, I think you would need to 1) set a small collision detection threshold and/or 2) consider increasing SDF grid resolution. For 1), you can try changing "col_th" in your XML to 0. For 2), you can try reducing "dx" in your XML. I suggest trying 1) first. If it does not work, try 2).

In this case, I think you would need to 1) set a small collision detection threshold and/or 2) consider increasing SDF grid resolution. For 1), you can try changing "col_th" in your XML to 0. For 2), you can try reducing "dx" in your XML. I suggest trying 1) first. If it does not work, try 2).

Thanks for the further suggestions in the first place.

I've tried out the possible solutions, which give us the following collection of tests, as shown in the table below. Unfortunately, they don't give rise to the incidental motions of the gear(s).

autoplan_simulation_tests_collection

One simplified animation example for (max_edge:=0.05, collision-th:=0.0, sdf-dx:=0.01), where only large (actively moving) and medium gears are involved, is given below:
0_1

@yunshengtian, the problem has now been solved. After an extensive range of tries, the cause has been pinpointed which is the improper design of 3d models for the assembly. Specifically, the gears in the assembled state have overlap with each other on their respective teeth, which incurs the failure of simulation initially. And the simulator is not capable of telling us whether such overlap/mesh penetration happens initially. So after I corrected the 3d model design for the assembly, the simulation now runs properly, even with your default parameters.
To offer you a proof, the resulting animation is shown below:
0_0

The reason why I reopen this issue is that I found another cause that hinders the incidental motion of the gear(s) involved in the animation. That is, when the PhysicsPlanner::render(path, record_path=None) is invoked, (e.g., as invoked in this code line:

self.render(path, record_path=record_path)
), if path is not set as None, the incidental motion won't take place in the animation. So I need to set path as None when calling this method. Could you tell me why, @yunshengtian?

Good to hear the issue was resolved that way. The penetration allowance needs to be determined by the user since it's pretty different for different CAD assemblies, though there are APIs of simulation that can tell you the amount of penetration.

Regarding this new issue, what's the animation that you get if you don't set path as None? Since the path only stores the successful disassembly motion, which is probably not the rotating motion you showed here. If you set the path as None, it will just play all the trial motions (not necessarily disassembly motions) during the physics-based planning.

Thanks for the explanation. To answer your question, here is the comparison between two series of disassembly gif. Note that the gears involved in the active swaying motion are set with the joint type being "revolute" around their respective rotating axis.
(1) Path is set as None:
0_0
1_1
2_2
(2) Path is not set as None:
0_0
1_1
2_2