Unverified Commit b4e78e60 authored by Farbod Farshidian's avatar Farbod Farshidian Committed by GitHub

Adds utility class to convert URDF to USD (#26)

# Description

Adds a helper class that converts a urdf description into an
instanceable usd file with separate meshes.

If a `usd_dir` is provided, the conversion is lazy: It only performs
conversion if the provided `UrdfLoaderCfg` or the main URDF file is
modified. The current implementation does not automatically trigger USD
generation if only mesh files are changed.

Fixes #35 

## Type of change

- New feature (non-breaking change which adds functionality)
- This change requires a documentation update

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file

---------
Co-authored-by: 's avatarMayank Mittal <mittalma@leggedrobotics.com>
parent f2d97bdc
......@@ -113,6 +113,7 @@ autodoc_mock_imports = [
"omni.isaac.core",
"omni.isaac.kit",
"omni.isaac.cloner",
"omni.isaac.urdf",
"gym",
"skrl",
"stable_baselines3",
......
......@@ -9,6 +9,7 @@ omni.isaac.orbit extension
orbit.actuators.group
orbit.actuators.model
orbit.asset_loader
orbit.devices
orbit.markers
orbit.objects.articulated
......
omni.isaac.orbit.asset_loader
=============================
.. automodule:: omni.isaac.orbit.asset_loader
:members:
:undoc-members:
:show-inheritance:
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.3.2"
version = "0.4.0"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.3.2 (2023-04-27)
0.4.0 (2023-05-27)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added a helper class :class:`omni.isaac.orbit.asset_loader.UrdfLoader` that coverts a URDF file to instanceable USD
file based on the input configuration object.
0.3.2 (2023-04-27)
~~~~~~~~~~~~~~~~~~
Fixed
^^^^^
* Added safe-printing of functions while using the :meth:`omni.isaac.orbit.utils.dict.print_dict` function.
......
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
Sub-module containing utilities for loading different assets.
This submodule depends on :mod:`omni.kit.*` and :mod:`omni.isaac.*`. Typically, these packages
are only available once the simulation app is running.
Currently, it includes the following utility classes:
* :class:`UrdfLoader`: Converts a urdf description into an instantiable usd file with separate meshes.
"""
from .urdf_loader import UrdfLoader, UrdfLoaderCfg
__all__ = [
# urdf to usd converter
"UrdfLoaderCfg",
"UrdfLoader",
]
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import hashlib
import json
import os
import pathlib
import random
from dataclasses import MISSING
from datetime import datetime
from typing import Optional
import omni.kit.commands
from omni.isaac.urdf import _urdf as omni_urdf
from omni.isaac.orbit.utils import configclass
from omni.isaac.orbit.utils.io import dump_yaml
__all__ = ["UrdfLoaderCfg", "UrdfLoader"]
_DRIVE_TYPE = {
"none": 0,
"position": 1,
"velocity": 2,
}
"""Mapping from drive type name to URDF importer drive number."""
_NORMALS_DIVISION = {
"catmullClark": 0,
"loop": 1,
"bilinear": 2,
"none": 3,
}
"""Mapping from normals division name to urdf importer normals division number."""
@configclass
class UrdfLoaderCfg:
"""The configuration class for UrdfLoader."""
urdf_path: str = MISSING
"""The path to the urdf file (e.g. path/to/urdf/robot.urdf)."""
usd_dir: Optional[str] = None
"""The output directory path to store the generated USD file. Defaults to :obj:`None`.
If set to :obj:`None`, it is resolved as ``/tmp/Orbit/usd_{date}_{time}_{random}``, where
the parameters in braces are runtime generated.
"""
usd_file_name: Optional[str] = None
"""The name of the generated usd file. Defaults to :obj:`None`.
If set to :obj:`None`, it is resolved from the urdf file name.
"""
force_usd_conversion: bool = False
"""Force the conversion of the urdf file to usd. Defaults to False."""
link_density = 0.0
"""Default density used for links. Defaults to 0.
This setting is only effective if ``"inertial"`` properties are missing in the URDF.
"""
import_inertia_tensor: bool = True
"""Import the inertia tensor from urdf. Defaults to True.
If the ``"inertial"`` tag is missing, then it is imported as an identity.
"""
convex_decompose_mesh = False
"""Decompose a convex mesh into smaller pieces for a closer fit. Defaults to False."""
fix_base: bool = MISSING
"""Create a fix joint to the root/base link. Defaults to True."""
merge_fixed_joints: bool = False
"""Consolidate links that are connected by fixed joints. Defaults to False."""
self_collision: bool = False
"""Activate self-collisions between links of the articulation. Defaults to False."""
default_drive_type: str = "none"
"""The drive type used for joints. Defaults to ``"none"``.
The drive type dictates the loaded joint PD gains and USD attributes for joint control:
* ``"none"``: The joint stiffness and damping are set to 0.0.
* ``"position"``: The joint stiff and damping are set based on the URDF file or provided configuration.
* ``"velocity"``: The joint stiff is set to zero and damping is based on the URDF file or provided configuration.
"""
default_drive_stiffness: float = 0.0
"""The default stiffness of the joint drive. Defaults to 0.0."""
default_drive_damping: float = 0.0
"""The default damping of the joint drive. Defaults to 0.0.
Note:
If set to zero, the values parsed from the URDF joint tag ``"<dynamics><damping>"`` are used.
Otherwise, it is overridden by the configured value.
"""
class UrdfLoader:
"""Loader for a URDF description file as an instanceable USD file.
This class wraps around the ``omni.isaac.urdf_importer`` extension to provide a lazy implementation
for URDF to USD conversion. It stores the output USD file in an instanceable format since that is
what is typically used in all learning related applications.
The file conversion is lazy if the output usd directory, :obj:`UrdfLoaderCfg.usd_dir`, is provided.
In the lazy conversion, the USD file is only re-generated if the usd files do not exist or if they exist,
the provided configuration or the main urdf file is modified. To override this behavior, set
:obj:`UrdfLoaderCfg.force_usd_conversion` as True.
In the case that no USD directory is defined, lazy conversion is deactivated and the generated USD file is
stored in folder ``/tmp/Orbit/usd_{date}_{time}_{random}``, where the parameters in braces are generated
at runtime. The random identifiers help avoid a race condition where two simultaneously triggered conversions
try to use the same directory for reading/writing the generated files.
.. caution::
The current lazy conversion implementation does not automatically trigger USD generation if only the
mesh files used by the URDF are modified. To force generation, either set
:obj:`UrdfLoaderCfg.force_usd_conversion` to True or remove the USD folder.
.. note::
Additionally, changes to the parameters :obj:`UrdfLoaderCfg.urdf_path`, :obj:`UrdfLoaderCfg.usd_dir`, and
:obj:`UrdfLoaderCfg.usd_file_name` are not considered as modifications in the configuration instance that
trigger USD file re-generation.
"""
def __init__(self, cfg: UrdfLoaderCfg):
"""Initializes the class.
Args:
cfg (UrdfLoaderCfg): The configuration instance for URDF to USD conversion.
Raises:
ValueError: When provided URDF file does not exist.
"""
# check if the urdf file exists
if not os.path.isfile(cfg.urdf_path):
raise ValueError(f"The URDF path does not exist: ({cfg.urdf_path})!")
# resolve USD directory name
if cfg.usd_dir is None:
# a folder in "/tmp/Orbit" by the name: usd_{date}_{time}_{random}
time_tag = datetime.now().strftime("%Y%m%d_%H%M%S")
self._usd_dir = f"/tmp/Orbit/usd_{time_tag}_{random.randrange(10000)}"
else:
self._usd_dir = cfg.usd_dir
# resolve the file name from urdf file name if not provided
if cfg.usd_file_name is None:
usd_file_name = pathlib.PurePath(cfg.urdf_path).stem
else:
usd_file_name = cfg.usd_file_name
# add USD extension if not provided
if not (usd_file_name.endswith(".usd") or usd_file_name.endswith(".usda")):
self._usd_file_name = usd_file_name + ".usd"
else:
self._usd_file_name = usd_file_name
# create the USD directory
os.makedirs(self.usd_dir, exist_ok=True)
# check if usd files exist
self._usd_file_exists = os.path.isfile(self.usd_path)
# path to read/write urdf hash file
dest_hash_path = f"{self.usd_dir}/.urdf_hash"
# convert urdf to hash
urdf_hash = UrdfLoader._config_to_hash(cfg)
# read the saved hash
try:
with open(dest_hash_path) as f:
existing_urdf_hash = f.readline()
self._is_same_urdf = existing_urdf_hash == urdf_hash
except FileNotFoundError:
self._is_same_urdf = False
# generate usd files
if cfg.force_usd_conversion or not self._usd_file_exists or not self._is_same_urdf:
# write the updated hash
with open(dest_hash_path, "w") as f:
f.write(urdf_hash)
# Convert urdf to an instantiable usd
import_config = self._get_urdf_import_config(cfg)
omni.kit.commands.execute(
"URDFParseAndImportFile",
urdf_path=cfg.urdf_path,
import_config=import_config,
dest_path=self.usd_path,
)
# Dump the configuration to a file
dump_yaml(os.path.join(self.usd_dir, "config.yaml"), cfg.to_dict())
"""
Properties.
"""
@property
def usd_dir(self) -> str:
"""The path to the directory where the generated USD files are stored."""
return self._usd_dir
@property
def usd_file_name(self) -> str:
"""The file name of the generated USD file."""
return self._usd_file_name
@property
def usd_path(self) -> str:
"""The path to the generated USD file."""
return os.path.join(self.usd_dir, self.usd_file_name)
@property
def usd_instanceable_meshes_path(self) -> str:
"""The path to the USD mesh file."""
return os.path.join(self.usd_dir, "Props", "instanceable_meshes.usd")
"""
Private helpers.
"""
def _get_urdf_import_config(self, cfg: UrdfLoaderCfg) -> omni_urdf.ImportConfig:
"""Set the settings into the import config."""
import_config = omni_urdf.ImportConfig()
# set the unit scaling factor, 1.0 means meters, 100.0 means cm
import_config.set_distance_scale(1.0)
# set imported robot as default prim
import_config.set_make_default_prim(True)
# add a physics scene to the stage on import if none exists
import_config.set_create_physics_scene(False)
# -- instancing settings
# meshes will be placed in a separate usd file
import_config.set_make_instanceable(True)
import_config.set_instanceable_usd_path(self.usd_instanceable_meshes_path)
# -- asset settings
# default density used for links, use 0 to auto-compute
import_config.set_density(cfg.link_density)
# import inertia tensor from urdf, if it is not specified in urdf it will import as identity
import_config.set_import_inertia_tensor(cfg.import_inertia_tensor)
# decompose a convex mesh into smaller pieces for a closer fit
import_config.set_convex_decomp(cfg.convex_decompose_mesh)
import_config.set_subdivision_scheme(_NORMALS_DIVISION["bilinear"])
# -- physics settings
# create fix joint for base link
import_config.set_fix_base(cfg.fix_base)
# consolidating links that are connected by fixed joints
import_config.set_merge_fixed_joints(cfg.merge_fixed_joints)
# self collisions between links in the articulation
import_config.set_self_collision(cfg.self_collision)
# default drive type used for joints
import_config.set_default_drive_type(_DRIVE_TYPE[cfg.default_drive_type])
# default proportional gains
import_config.set_default_drive_strength(cfg.default_drive_stiffness)
# default derivative gains
import_config.set_default_position_drive_damping(cfg.default_drive_damping)
return import_config
@staticmethod
def _config_to_hash(cfg: UrdfLoaderCfg) -> str:
"""Converts the configuration object and urdf file to an MD5 hash of a string.
.. warning::
It only checks the main urdf file not the mesh files.
Args:
config (UrdfLoaderCfg): The urdf loader configuration object.
Returns:
An MD5 hash of a string.
"""
# convert ro dict and remove path related info
config_dic = cfg.to_dict()
_ = config_dic.pop("urdf_path")
_ = config_dic.pop("usd_dir")
_ = config_dic.pop("usd_file_name")
# convert config dic to bytes
config_bytes = json.dumps(config_dic).encode()
# hash config
md5 = hashlib.md5()
md5.update(config_bytes)
# read the urdf file to observe changes
with open(cfg.urdf_path, "rb") as f:
while True:
# read 64kb chunks to avoid memory issues for the large files!
data = f.read(65536)
if not data:
break
md5.update(data)
return md5.hexdigest()
# Copyright [2023] Boston Dynamics AI Institute, Inc.
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
from omni.isaac.kit import SimulationApp
# launch omniverse app
config = {"headless": True}
simulation_app = SimulationApp(config)
"""Rest everything follows."""
import math
import numpy as np
import os
import traceback
import unittest
import carb
import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.core.articulations import ArticulationView
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.extensions import get_extension_path_from_name
from omni.isaac.orbit.asset_loader import UrdfLoader, UrdfLoaderCfg
class TestUrdfLoader(unittest.TestCase):
"""Test fixture for the UrdfLoader class."""
def setUp(self):
"""Create a blank new stage for each test."""
# retrieve path to urdf importer extension
extension_path = get_extension_path_from_name("omni.isaac.urdf")
# default configuration
self.config = UrdfLoaderCfg(
urdf_path=f"{extension_path}/data/urdf/robots/franka_description/robots/panda_arm_hand.urdf", fix_base=True
)
# Simulation time-step
self.dt = 0.01
# Load kit helper
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="numpy")
def tearDown(self) -> None:
"""Stops simulator after each test."""
# stop simulation
self.sim.stop()
self.sim.clear()
def test_no_change(self):
"""Call conversion twice. This should not generate a new USD file."""
urdf_loader = UrdfLoader(self.config)
time_usd_file_created = os.stat(urdf_loader.usd_path).st_mtime_ns
# no change to config only define the usd directory
new_config = self.config
new_config.usd_dir = urdf_loader.usd_dir
# convert to usd but this time in the same directory as previous step
new_urdf_loader = UrdfLoader(new_config)
new_time_usd_file_created = os.stat(new_urdf_loader.usd_path).st_mtime_ns
self.assertEqual(time_usd_file_created, new_time_usd_file_created)
def test_config_change(self):
"""Call conversion twice but change the config in the second call. This should generate a new USD file."""
urdf_loader = UrdfLoader(self.config)
time_usd_file_created = os.stat(urdf_loader.usd_path).st_mtime_ns
# change the config
new_config = self.config
new_config.fix_base = not self.config.fix_base
# define the usd directory
new_config.usd_dir = urdf_loader.usd_dir
# convert to usd but this time in the same directory as previous step
new_urdf_loader = UrdfLoader(new_config)
new_time_usd_file_created = os.stat(new_urdf_loader.usd_path).st_mtime_ns
self.assertNotEqual(time_usd_file_created, new_time_usd_file_created)
def test_create_prim_from_usd(self):
"""Call conversion and create a prim from it."""
urdf_loader = UrdfLoader(self.config)
prim_path = "/World/Robot"
prim_utils.create_prim(prim_path, usd_path=urdf_loader.usd_path)
self.assertTrue(prim_utils.is_prim_path_valid(prim_path))
def test_config_drive_type(self):
"""Change the drive mechanism of the robot to be position."""
# Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__))
output_dir = os.path.join(test_dir, "output", "urdf_loader")
if not os.path.exists(output_dir):
os.makedirs(output_dir, exist_ok=True)
# change the config
self.config.default_drive_type = "position"
self.config.default_drive_stiffness = 400.0
self.config.default_drive_damping = 40.0
self.config.usd_dir = output_dir
urdf_loader = UrdfLoader(self.config)
# check the drive type of the robot
prim_path = "/World/Robot"
prim_utils.create_prim(prim_path, usd_path=urdf_loader.usd_path)
# access the robot
robot = ArticulationView(prim_path, reset_xform_properties=False)
# play the simulator and initialize the robot
self.sim.reset()
robot.initialize()
# check drive values for the robot (read from physx)
drive_stiffness, drive_damping = robot.get_gains()
# -- for the arm (revolute joints)
# user provides the values in radians but simulator sets them as in degrees
expected_drive_stiffness = math.degrees(self.config.default_drive_stiffness)
expected_drive_damping = math.degrees(self.config.default_drive_damping)
np.testing.assert_array_equal(drive_stiffness[:, :7], expected_drive_stiffness)
np.testing.assert_array_equal(drive_damping[:, :7], expected_drive_damping)
# -- for the hand (prismatic joints)
expected_drive_stiffness = self.config.default_drive_stiffness
expected_drive_damping = self.config.default_drive_damping
np.testing.assert_array_equal(drive_stiffness[:, 7:], expected_drive_stiffness)
np.testing.assert_array_equal(drive_damping[:, 7:], expected_drive_damping)
# check drive values for the robot (read from usd)
self.sim.stop()
drive_stiffness, drive_damping = robot.get_gains()
# -- for the arm (revolute joints)
# user provides the values in radians but simulator sets them as in degrees
expected_drive_stiffness = math.degrees(self.config.default_drive_stiffness)
expected_drive_damping = math.degrees(self.config.default_drive_damping)
np.testing.assert_array_equal(drive_stiffness[:, :7], expected_drive_stiffness)
np.testing.assert_array_equal(drive_damping[:, :7], expected_drive_damping)
# -- for the hand (prismatic joints)
expected_drive_stiffness = self.config.default_drive_stiffness
expected_drive_damping = self.config.default_drive_damping
np.testing.assert_array_equal(drive_stiffness[:, 7:], expected_drive_stiffness)
np.testing.assert_array_equal(drive_damping[:, 7:], expected_drive_damping)
if __name__ == "__main__":
try:
unittest.main()
except Exception as err:
carb.log_error(err)
carb.log_error(traceback.format_exc())
raise
finally:
# close sim app
simulation_app.close()
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment