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 = [ ...@@ -113,6 +113,7 @@ autodoc_mock_imports = [
"omni.isaac.core", "omni.isaac.core",
"omni.isaac.kit", "omni.isaac.kit",
"omni.isaac.cloner", "omni.isaac.cloner",
"omni.isaac.urdf",
"gym", "gym",
"skrl", "skrl",
"stable_baselines3", "stable_baselines3",
......
...@@ -9,6 +9,7 @@ omni.isaac.orbit extension ...@@ -9,6 +9,7 @@ omni.isaac.orbit extension
orbit.actuators.group orbit.actuators.group
orbit.actuators.model orbit.actuators.model
orbit.asset_loader
orbit.devices orbit.devices
orbit.markers orbit.markers
orbit.objects.articulated orbit.objects.articulated
......
omni.isaac.orbit.asset_loader
=============================
.. automodule:: omni.isaac.orbit.asset_loader
:members:
:undoc-members:
:show-inheritance:
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.3.2" version = "0.4.0"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.3.2 (2023-04-27) 0.4.0 (2023-05-27)
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
Added 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. * 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
"""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