Skip to content

[BUG] Mismatch between visualization and URDF #9

@SimonXie2004

Description

@SimonXie2004

Hi! I have encountered and identified a bug that causes mismatch between generated visualization and actual exported URDF. For those using URDFormer as comparison experiments, this might be a issue.

Here's the explanation:

Content:

  1. Problem Description
  2. The (possible) code that causes this bug

Problem Description

I have used case: StorageFurniture_45717, view 07 from partnet dataset as input. Here's the rendered result (direct output of running demo.py) :

Image

However, the exported URDF looks like the following.

Image

The URDF is as follows

<?xml version='1.0' encoding='utf-8'?>
<robot name="my_urdf">
    <link name="base_link">
        <visual>
            <origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
            <material name="white">
                <color rgba="0.8 0.8 0.8 1" />
            </material>
            <geometry>
                <mesh filename="../meshes/cabinet.obj" scale="1 1 1" />
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
            <geometry>
                <mesh filename="../meshes/cabinet.obj" scale="1 1 1" />
            </geometry>
        </collision>
        <inertial>
            <mass value="1" />
            <inertia ixx="1e-4" ixy="0" ixz="0" iyy="1e-4" iyz="0" izz="1e-4" />
        </inertial>
    </link>
    <link name="doorL0">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <material name="white">
                <color rgba="0.8 0.8 0.8 1" />
            </material>
            <geometry>
                <mesh filename="../meshes/parts/doorL.obj" scale="1 3.99 3.99" />
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="../meshes/parts/doorL.obj" scale="1 3.99 3.99" />
            </geometry>
        </collision>
        <inertial>
            <mass value="0.2" />
            <inertia ixx="1e-4" ixy="0" ixz="0" iyy="1e-4" iyz="0" izz="1e-4" />
        </inertial>
    </link>
    <joint name="doorL0_to_base_link" type="revolute">
        <axis xyz="0 0 1" />
        <limit effort="5" lower="-1.57" upper="0" velocity="2.283" />
        <origin xyz="0 0.0 0.0" rpy="0.0 0.0 0.0" />
        <parent link="base_link" />
        <child link="doorL0" />
    </joint>
    <link name="knob1">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <material name="white">
                <color rgba="0.8 0.8 0.8 1" />
            </material>
            <geometry>
                <mesh filename="../meshes/parts/knob.obj" scale="1 1 1" />
            </geometry>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <mesh filename="../meshes/parts/knob.obj" scale="1 1 1" />
            </geometry>
        </collision>
        <inertial>
            <mass value="0.2" />
            <inertia ixx="1e-4" ixy="0" ixz="0" iyy="1e-4" iyz="0" izz="1e-4" />
        </inertial>
    </link>
    <joint name="knob1_to_doorL0" type="fixed">
        <axis xyz="1 0 0" />
        <limit effort="5" lower="0" upper="1.57" velocity="2.283" />
        <origin xyz="0 0.8333333333333334 0.16666666666666666" rpy="0.0 0.0 0.0" />
        <parent link="doorL0" />
        <child link="knob1" />
    </joint>
</robot>

However, in this URDF, there is no actually ../mesh/oven.obj, which is the following image (that should belong to this mesh)

Image

Possible code that causes this bug

In <repo_root>/utils.py, Line 385-397:

part_names = ['none', 'drawer', 'doorL', 'doorR',
                  'handle', 'knob', 'washer_door', 'doorD', 'oven_door', 'doorU']
    base_names = ['none', 'cabinet_kitchen', 'oven', 'dishwasher', 'washer', 'fridge',
                  'oven_fan', 'shelf_base'
                  ]
    part_path = "meshes/parts/"

    # fix the oven fan problem: if there are parts, root shouldn't be oven fan
    if len(position_pred_ori) > 1 and mesh_base == 6:
        mesh_base = 1


    root = "meshes/{}.obj".format(base_names[mesh_base])

This has actually extracted the base_link from class URDFormer's forward() result. (Note that mesh_base is a return value from URDFormer's forward.)

However, in <repo_root>/utils.py, Line 610:

        write_urdfs(filename, root, root_scale, root_position, root_orientation, links, link_scales, link_positions,
                link_orientations, linkparents, jointtypes, linkJointAxis)

In this function, root is actually not used. Hence, the root_link is actually not exported to the URDF.

This might explain why the oven.obj is missing from the exported URDF.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions