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

Fixes to the urdf to mjcf conversion #5

Merged
merged 6 commits into from
Dec 12, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
142 changes: 72 additions & 70 deletions tests/sample/robot_test.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,79 +39,81 @@
<body name="root" pos="0 0 0.63" quat="1 0 0 0">
<freejoint name="root" />
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this was created with new code but old urdf right?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

correct. the input was

urdf2mjcf/tests/sample/robot.urdf

<site name="imu" size="0.01" pos="0 0 0" />
<geom type="mesh" mesh="trunk" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="trunk" />
<geom pos="0 0.255 0.45" quat="2.67949e-08 -1 0 0" type="mesh" mesh="clav" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="clav" pos="0 0.255 0.45" quat="2.67949e-08 -1 0 0" />
<geom pos="0 0.255 0.45" type="mesh" mesh="scap" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="scap" pos="0 0.255 0.45" />
<geom pos="0 0.255 0.45" type="mesh" mesh="uarm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="uarm" pos="0 0.255 0.45" />
<geom pos="0 0.255 0.22" type="mesh" mesh="farm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="farm" pos="0 0.255 0.22" />
<geom pos="0 -0.255 0.45" quat="1 0 0 0" type="mesh" mesh="clav" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="clav" pos="0 -0.255 0.45" quat="1 0 0 0" />
<geom pos="0 -0.255 0.45" type="mesh" mesh="scap" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="scap" pos="0 -0.255 0.45" />
<geom pos="0 -0.255 0.45" type="mesh" mesh="uarm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="uarm" pos="0 -0.255 0.45" />
<geom pos="0 -0.255 0.22" type="mesh" mesh="farm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="farm" pos="0 -0.255 0.22" />
<body name="L_buttock" pos="0 0.1577 0">
<inertial pos="0.00129183 -0.00184328 2.27946e-05" quat="0.706341 0.707841 -0.00498313 -0.00434939" mass="1.29909" diaginertia="0.00209325 0.00150009 0.00131174" />
<joint name="L_hip_y" pos="0 0 0" axis="0 1 0" range="-3.14 3.14" />
<geom quat="2.67949e-08 1 0 0" type="mesh" mesh="buttock" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="buttock" quat="2.67949e-08 1 0 0" />
<body name="L_leg">
<inertial pos="0.000708602 -2.24355e-05 -0.110352" quat="0.706876 0.0329943 0.0330587 0.705794" mass="1.33983" diaginertia="0.00375341 0.00352246 0.00184361" />
<joint name="L_hip_x" pos="0 0 0" axis="1 0 0" range="-0.523 2.093" />
<geom type="mesh" mesh="leg" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="leg" />
<body name="L_thigh">
<inertial pos="-0.000407357 0.00130538 -0.291653" quat="0.711843 -0.00549725 0.000501512 0.702317" mass="1.93995" diaginertia="0.00607631 0.0044935 0.00293511" />
<joint name="L_hip_z" pos="0 0 0" axis="0 0 1" range="-3.14 3.14" />
<geom type="mesh" mesh="mthigh" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="mthigh" />
<body name="L_calf" pos="0 0 -0.3">
<inertial pos="-0.00195352 -0.00434338 -0.134048" quat="0.599799 -0.00402307 0.025204 0.799743" mass="1.54477" diaginertia="0.00986297 0.00971929 0.00143814" />
<joint name="L_knee" pos="0 0 0" axis="0 1 0" range="-1.919 1.919" />
<geom type="mesh" mesh="mcalf" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="mcalf" />
<body name="L_foot" pos="0 0 -0.3">
<inertial pos="0.0233665 0.014827 -0.0165314" quat="-0.00182247 0.713608 0.0126839 0.700428" mass="0.542373" diaginertia="0.00215059 0.00196588 0.000256086" />
<joint name="L_ankle_y" pos="0 0 0" axis="0 1 0" range="-0.698 0.698" frictionloss="0.01" />
<geom size="0.11 0.04 0.0075" pos="0.03 -0.011 -0.02" type="box" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="box" rgba="" size="0.11 0.04 0.0075" pos="0.03 -0.011 -0.02" />
<body name="base" pos="0 0 0" quat="1 0 0 0">
<geom type="mesh" mesh="trunk" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="trunk" />
<geom pos="0 0.255 0.45" quat="2.67949e-08 -1 0 0" type="mesh" mesh="clav" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="clav" pos="0 0.255 0.45" quat="2.67949e-08 -1 0 0" />
<geom pos="0 0.255 0.45" type="mesh" mesh="scap" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="scap" pos="0 0.255 0.45" />
<geom pos="0 0.255 0.45" type="mesh" mesh="uarm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="uarm" pos="0 0.255 0.45" />
<geom pos="0 0.255 0.22" type="mesh" mesh="farm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="farm" pos="0 0.255 0.22" />
<geom pos="0 -0.255 0.45" quat="1 0 0 0" type="mesh" mesh="clav" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="clav" pos="0 -0.255 0.45" quat="1 0 0 0" />
<geom pos="0 -0.255 0.45" type="mesh" mesh="scap" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="scap" pos="0 -0.255 0.45" />
<geom pos="0 -0.255 0.45" type="mesh" mesh="uarm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="uarm" pos="0 -0.255 0.45" />
<geom pos="0 -0.255 0.22" type="mesh" mesh="farm" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="farm" pos="0 -0.255 0.22" />
<body name="L_buttock" pos="0 0.1577 0">
<inertial pos="0.00129183 -0.00184328 2.27946e-05" quat="0.706341 0.707841 -0.00498313 -0.00434939" mass="1.29909" diaginertia="0.00209325 0.00150009 0.00131174" />
<joint name="L_hip_y" pos="0 0 0" axis="0 1 0" range="-3.14 3.14" />
<geom quat="2.67949e-08 1 0 0" type="mesh" mesh="buttock" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="buttock" quat="2.67949e-08 1 0 0" />
<body name="L_leg">
<inertial pos="0.000708602 -2.24355e-05 -0.110352" quat="0.706876 0.0329943 0.0330587 0.705794" mass="1.33983" diaginertia="0.00375341 0.00352246 0.00184361" />
<joint name="L_hip_x" pos="0 0 0" axis="1 0 0" range="-0.523 2.093" />
<geom type="mesh" mesh="leg" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="leg" />
<body name="L_thigh">
<inertial pos="-0.000407357 0.00130538 -0.291653" quat="0.711843 -0.00549725 0.000501512 0.702317" mass="1.93995" diaginertia="0.00607631 0.0044935 0.00293511" />
<joint name="L_hip_z" pos="0 0 0" axis="0 0 1" range="-3.14 3.14" />
<geom type="mesh" mesh="mthigh" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="mthigh" />
<body name="L_calf" pos="0 0 -0.3">
<inertial pos="-0.00195352 -0.00434338 -0.134048" quat="0.599799 -0.00402307 0.025204 0.799743" mass="1.54477" diaginertia="0.00986297 0.00971929 0.00143814" />
<joint name="L_knee" pos="0 0 0" axis="0 1 0" range="-1.919 1.919" />
<geom type="mesh" mesh="mcalf" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="mcalf" />
<body name="L_foot" pos="0 0 -0.3">
<inertial pos="0.0233665 0.014827 -0.0165314" quat="-0.00182247 0.713608 0.0126839 0.700428" mass="0.542373" diaginertia="0.00215059 0.00196588 0.000256086" />
<joint name="L_ankle_y" pos="0 0 0" axis="0 1 0" range="-0.698 0.698" frictionloss="0.01" />
<geom size="0.11 0.04 0.0075" pos="0.03 -0.011 -0.02" type="box" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="box" rgba="" size="0.11 0.04 0.0075" pos="0.03 -0.011 -0.02" />
</body>
</body>
</body>
</body>
</body>
</body>
<body name="R_buttock" pos="0 -0.1577 0">
<inertial pos="0.00129183 0.00184328 2.27946e-05" quat="0.707841 0.706341 0.00434939 0.00498313" mass="1.29909" diaginertia="0.00209325 0.00150009 0.00131174" />
<joint name="R_hip_y" pos="0 0 0" axis="0 1 0" range="-3.14 3.14" />
<geom type="mesh" mesh="buttock" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="buttock" />
<body name="R_leg">
<inertial pos="0.000708602 2.24355e-05 -0.110352" quat="0.705794 0.0330587 0.0329943 0.706876" mass="1.33983" diaginertia="0.00375341 0.00352246 0.00184361" />
<joint name="R_hip_x" pos="0 0 0" axis="1 0 0" range="-2.093 0.523" />
<geom type="mesh" mesh="leg" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="leg" />
<body name="R_thigh">
<inertial pos="-0.000407357 -0.00130538 -0.291653" quat="0.702317 0.000501512 -0.00549725 0.711843" mass="1.93995" diaginertia="0.00607631 0.0044935 0.00293511" />
<joint name="R_hip_z" pos="0 0 0" axis="0 0 1" range="-3.14 3.14" />
<geom type="mesh" mesh="thigh" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="thigh" />
<body name="R_calf" pos="0 0 -0.3">
<inertial pos="-0.00195352 0.00434338 -0.134048" quat="0.799743 0.025204 -0.00402307 0.599799" mass="1.54477" diaginertia="0.00986297 0.00971929 0.00143814" />
<joint name="R_knee" pos="0 0 0" axis="0 1 0" range="-1.919 1.919" />
<geom type="mesh" mesh="calf" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="calf" />
<body name="R_foot" pos="0 0 -0.3">
<inertial pos="0.0233665 0.014827 -0.0165314" quat="-0.00182247 0.713608 0.0126839 0.700428" mass="0.542373" diaginertia="0.00215059 0.00196588 0.000256086" />
<joint name="R_ankle_y" pos="0 0 0" axis="0 1 0" range="-0.698 0.698" frictionloss="0.01" />
<geom size="0.11 0.04 0.0075" pos="0.03 0.011 -0.02" type="box" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="box" rgba="" size="0.11 0.04 0.0075" pos="0.03 0.011 -0.02" />
<body name="R_buttock" pos="0 -0.1577 0">
<inertial pos="0.00129183 0.00184328 2.27946e-05" quat="0.707841 0.706341 0.00434939 0.00498313" mass="1.29909" diaginertia="0.00209325 0.00150009 0.00131174" />
<joint name="R_hip_y" pos="0 0 0" axis="0 1 0" range="-3.14 3.14" />
<geom type="mesh" mesh="buttock" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="buttock" />
<body name="R_leg">
<inertial pos="0.000708602 2.24355e-05 -0.110352" quat="0.705794 0.0330587 0.0329943 0.706876" mass="1.33983" diaginertia="0.00375341 0.00352246 0.00184361" />
<joint name="R_hip_x" pos="0 0 0" axis="1 0 0" range="-2.093 0.523" />
<geom type="mesh" mesh="leg" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="leg" />
<body name="R_thigh">
<inertial pos="-0.000407357 -0.00130538 -0.291653" quat="0.702317 0.000501512 -0.00549725 0.711843" mass="1.93995" diaginertia="0.00607631 0.0044935 0.00293511" />
<joint name="R_hip_z" pos="0 0 0" axis="0 0 1" range="-3.14 3.14" />
<geom type="mesh" mesh="thigh" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="thigh" />
<body name="R_calf" pos="0 0 -0.3">
<inertial pos="-0.00195352 0.00434338 -0.134048" quat="0.799743 0.025204 -0.00402307 0.599799" mass="1.54477" diaginertia="0.00986297 0.00971929 0.00143814" />
<joint name="R_knee" pos="0 0 0" axis="0 1 0" range="-1.919 1.919" />
<geom type="mesh" mesh="calf" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="mesh" rgba="" mesh="calf" />
<body name="R_foot" pos="0 0 -0.3">
<inertial pos="0.0233665 0.014827 -0.0165314" quat="-0.00182247 0.713608 0.0126839 0.700428" mass="0.542373" diaginertia="0.00215059 0.00196588 0.000256086" />
<joint name="R_ankle_y" pos="0 0 0" axis="0 1 0" range="-0.698 0.698" frictionloss="0.01" />
<geom size="0.11 0.04 0.0075" pos="0.03 0.011 -0.02" type="box" contype="1" conaffinity="0" density="0" group="1" class="visualgeom" />
<geom type="box" rgba="" size="0.11 0.04 0.0075" pos="0.03 0.011 -0.02" />
</body>
</body>
</body>
</body>
Expand Down Expand Up @@ -169,6 +171,6 @@
</sensor>

<keyframe>
<key name="default" qpos="0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0" />
<key name="default" qpos="0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0" />
</keyframe>
</mujoco>
2 changes: 1 addition & 1 deletion tests/test_conversion.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ def test_conversion_no_frc_limit(tmpdir: Path) -> None:
mjcf_path=mjcf_path,
no_frc_limit=True,
copy_meshes=False,
default_position=[0.0] * 10,
default_position=[0.0] * 17,
)

# Compare the outputted MJCF with the expected XML
Expand Down
55 changes: 44 additions & 11 deletions urdf2mjcf/convert.py
Original file line number Diff line number Diff line change
Expand Up @@ -205,12 +205,23 @@ def add_root_body(root: ET.Element) -> None:
},
)

# Move existing bodies and geoms under root_body
# Create base body
base_body = ET.SubElement(
root_body,
"body",
attrib={
"name": "base",
"pos": "0 0 0",
"quat": "1 0 0 0",
},
)

# Move existing bodies and geoms under base_body
elements_to_move = list(worldbody)
for elem in elements_to_move:
if elem.tag in {"body", "geom"}:
worldbody.remove(elem)
root_body.append(elem)
base_body.append(elem)
worldbody.append(root_body)


Expand Down Expand Up @@ -449,21 +460,43 @@ def add_visual_geom_logic(root: ET.Element) -> None:
body.insert(index + 1, new_geom)


def calculate_dof_from_xml(root: ET.Element) -> int:
"""Calculate the total DOF (qpos size) of a robot based on the XML tree.

Free joints add 7 DOFs, and joints with a 'range' attribute add 1 DOF each.

Args:
root: Root element of the MJCF XML.

Returns:
Total DOF (qpos size).
"""
dof = 0

# Count free joints
for _ in root.iter("freejoint"):
dof += 7

# Count joints with a 'range' attribute
for joint in root.iter("joint"):
if "range" in joint.attrib:
dof += 1

return dof


def add_default_position(root: ET.Element, default_position: List[float]) -> None:
"""Add a keyframe to the root element.
"""Add a keyframe to the root element with the default start position.

Args:
root: The root element of the MJCF file.
default_position: The default position of the robot.
default_position: The default positions of the robot.
"""
actuators = root.find("actuator")
if actuators is None:
raise ValueError("No actuators found in the MJCF file.")

num_actuators = len(list(actuators.iter("motor")))
if len(default_position) != num_actuators:
raise ValueError(f"Default position must have {num_actuators} values, got {len(default_position)}.")
num_dof = calculate_dof_from_xml(root)
if len(default_position) != num_dof:
raise ValueError(f"Default position must have {num_dof} values, got {len(default_position)}.")

# Add the keyframe with the default position
keyframe = ET.Element("keyframe")
key = ET.SubElement(keyframe, "key")
key.set("name", "default")
Expand Down
Loading