Unverified Commit 475b3f79 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Adds allegro and shadow hand asset configurations (#392)

# Description

This MR adds configuration for allegro and shadow hands. The shadow hand
asset is a bit tricky because it has fixed tendons and the joints need
the drive properties.

## Type of change

- New feature (non-breaking change which adds functionality)

## Screenshots

The following script moves the hand from their lower to upper joint
limits (simulate a power grasp and release motion):

```bash
./orbit.sh -p source/standalone/demos/hands.py
```


https://github.com/isaac-orbit/orbit/assets/12863862/e0e5df7b-e049-407f-9f40-c24958a1faa3

## 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 run all the tests with `./orbit.sh --test` and they pass
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent e3c40acf
......@@ -11,6 +11,8 @@
RigidBodyPropertiesCfg
CollisionPropertiesCfg
MassPropertiesCfg
JointDrivePropertiesCfg
FixedTendonPropertiesCfg
.. rubric:: Functions
......@@ -25,6 +27,8 @@
modify_collision_properties
define_mass_properties
modify_mass_properties
modify_joint_drive_properties
modify_fixed_tendon_properties
Articulation Root
-----------------
......@@ -66,3 +70,21 @@ Mass
.. autofunction:: define_mass_properties
.. autofunction:: modify_mass_properties
Joint Drive
-----------
.. autoclass:: JointDrivePropertiesCfg
:members:
:exclude-members: __init__
.. autofunction:: modify_joint_drive_properties
Fixed Tendon
------------
.. autoclass:: FixedTendonPropertiesCfg
:members:
:exclude-members: __init__
.. autofunction:: modify_fixed_tendon_properties
......@@ -23,6 +23,18 @@ A few quick showroom scripts to run and checkout:
./orbit.sh -p source/standalone/demos/arms.py
- Spawn different hands and command them to open and close:
.. code:: bash
./orbit.sh -p source/standalone/demos/hands.py
- Spawn procedurally generated terrains with different configurations:
.. code:: bash
./orbit.sh -p source/standalone/demos/procedural_terrain.py
- Spawn multiple markers that are useful for visualizations:
.. code:: bash
......
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.14.0"
version = "0.14.1"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.14.1 (2024-03-16)
~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added simulation schemas for joint drive and fixed tendons. These can be configured for assets imported
from file formats.
* Added logging of tendon properties to the articulation class (if they are present in the USD prim).
0.14.0 (2024-03-15)
~~~~~~~~~~~~~~~~~~~
......
......@@ -117,6 +117,11 @@ class Articulation(RigidObject):
"""Number of joints in articulation."""
return self.root_physx_view.shared_metatype.dof_count
@property
def num_fixed_tendons(self) -> int:
"""Number of fixed tendons in articulation."""
return self.root_physx_view.max_fixed_tendons
@property
def num_bodies(self) -> int:
"""Number of bodies in articulation."""
......@@ -580,9 +585,11 @@ class Articulation(RigidObject):
carb.log_info(f"Body names: {self.body_names}")
carb.log_info(f"Number of joints: {self.num_joints}")
carb.log_info(f"Joint names: {self.joint_names}")
carb.log_info(f"Number of fixed tendons: {self.num_fixed_tendons}")
# -- assert that parsing was successful
if set(physx_body_names) != set(self.body_names):
raise RuntimeError("Failed to parse all bodies properly in the articulation.")
# create buffers
self._create_buffers()
# process configuration
......@@ -724,7 +731,7 @@ class Articulation(RigidObject):
# perform some sanity checks to ensure actuators are prepared correctly
total_act_joints = sum(actuator.num_joints for actuator in self.actuators.values())
if total_act_joints != self.num_joints:
if total_act_joints != (self.num_joints - self.num_fixed_tendons):
carb.log_warn(
"Not all actuators are configured! Total number of actuated joints not equal to number of"
f" joints available: {total_act_joints} != {self.num_joints}."
......@@ -857,3 +864,39 @@ class Articulation(RigidObject):
])
# convert table to string
carb.log_info(f"Simulation parameters for joints in {self.cfg.prim_path}:\n" + table.get_string())
# read out all tendon parameters from simulation
if self.num_fixed_tendons > 0:
# -- gains
ft_stiffnesses = self.root_physx_view.get_fixed_tendon_stiffnesses()[0].tolist()
ft_dampings = self.root_physx_view.get_fixed_tendon_dampings()[0].tolist()
# -- limits
ft_limit_stiffnesses = self.root_physx_view.get_fixed_tendon_limit_stiffnesses()[0].tolist()
ft_limits = self.root_physx_view.get_fixed_tendon_limits()[0].tolist()
ft_rest_lengths = self.root_physx_view.get_fixed_tendon_rest_lengths()[0].tolist()
ft_offsets = self.root_physx_view.get_fixed_tendon_offsets()[0].tolist()
# create table for term information
tendon_table = PrettyTable(float_format=".3f")
tendon_table.title = f"Simulation Tendon Information (Prim path: {self.cfg.prim_path})"
tendon_table.field_names = [
"Index",
"Stiffness",
"Damping",
"Limit Stiffness",
"Limit",
"Rest Length",
"Offset",
]
# add info on each term
for index in range(self.num_fixed_tendons):
tendon_table.add_row([
index,
ft_stiffnesses[index],
ft_dampings[index],
ft_limit_stiffnesses[index],
ft_limits[index],
ft_rest_lengths[index],
ft_offsets[index],
])
# convert table to string
carb.log_info(f"Simulation parameters for tendons in {self.cfg.prim_path}:\n" + tendon_table.get_string())
......@@ -3,6 +3,8 @@
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
from dataclasses import MISSING
from omni.isaac.orbit.actuators import ActuatorBaseCfg
......
......@@ -40,12 +40,16 @@ from .schemas import (
define_rigid_body_properties,
modify_articulation_root_properties,
modify_collision_properties,
modify_fixed_tendon_properties,
modify_joint_drive_properties,
modify_mass_properties,
modify_rigid_body_properties,
)
from .schemas_cfg import (
ArticulationRootPropertiesCfg,
CollisionPropertiesCfg,
FixedTendonPropertiesCfg,
JointDrivePropertiesCfg,
MassPropertiesCfg,
RigidBodyPropertiesCfg,
)
......@@ -52,7 +52,7 @@ def define_articulation_root_properties(
@apply_nested
def modify_articulation_root_properties(
prim_path: str, cfg: schemas_cfg.ArticulationRootPropertiesCfg, stage: Usd.Stage | None = None
):
) -> bool:
"""Modify PhysX parameters for an articulation root prim.
The `articulation root`_ marks the root of an articulation tree. For floating articulations, this should be on
......@@ -79,6 +79,9 @@ def modify_articulation_root_properties(
cfg: The configuration for the articulation root.
stage: The stage where to find the prim. Defaults to None, in which case the
current stage is used.
Returns:
True if the properties were successfully set, False otherwise.
"""
# obtain stage
if stage is None:
......@@ -142,7 +145,7 @@ def define_rigid_body_properties(
@apply_nested
def modify_rigid_body_properties(
prim_path: str, cfg: schemas_cfg.RigidBodyPropertiesCfg, stage: Usd.Stage | None = None
):
) -> bool:
"""Modify PhysX parameters for a rigid body prim.
A `rigid body`_ is a single body that can be simulated by PhysX. It can be either dynamic or kinematic.
......@@ -166,6 +169,9 @@ def modify_rigid_body_properties(
cfg: The configuration for the rigid body.
stage: The stage where to find the prim. Defaults to None, in which case the
current stage is used.
Returns:
True if the properties were successfully set, False otherwise.
"""
# obtain stage
if stage is None:
......@@ -234,7 +240,7 @@ def define_collision_properties(
@apply_nested
def modify_collision_properties(
prim_path: str, cfg: schemas_cfg.CollisionPropertiesCfg, stage: Usd.Stage | None = None
):
) -> bool:
"""Modify PhysX properties of collider prim.
These properties are based on the `UsdPhysics.CollisionAPI`_ and `PhysxSchema.PhysxCollisionAPI`_ schemas.
......@@ -256,6 +262,9 @@ def modify_collision_properties(
cfg: The configuration for the collider.
stage: The stage where to find the prim. Defaults to None, in which case the
current stage is used.
Returns:
True if the properties were successfully set, False otherwise.
"""
# obtain stage
if stage is None:
......@@ -320,7 +329,7 @@ def define_mass_properties(prim_path: str, cfg: schemas_cfg.MassPropertiesCfg, s
@apply_nested
def modify_mass_properties(prim_path: str, cfg: schemas_cfg.MassPropertiesCfg, stage: Usd.Stage | None = None):
def modify_mass_properties(prim_path: str, cfg: schemas_cfg.MassPropertiesCfg, stage: Usd.Stage | None = None) -> bool:
"""Set properties for the mass of a rigid body prim.
These properties are based on the `UsdPhysics.MassAPI` schema. If the mass is not defined, the density is used
......@@ -345,6 +354,9 @@ def modify_mass_properties(prim_path: str, cfg: schemas_cfg.MassPropertiesCfg, s
cfg: The configuration for the mass properties.
stage: The stage where to find the prim. Defaults to None, in which case the
current stage is used.
Returns:
True if the properties were successfully set, False otherwise.
"""
# obtain stage
if stage is None:
......@@ -433,3 +445,140 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd.
)
# success
return True
"""
Joint drive properties.
"""
@apply_nested
def modify_joint_drive_properties(
prim_path: str, drive_props: schemas_cfg.JointDrivePropertiesCfg, stage: Usd.Stage | None = None
) -> bool:
"""Modify PhysX parameters for a joint prim.
This function checks if the input prim is a prismatic or revolute joint and applies the joint drive schema
on it. If the joint is a tendon (i.e., it has the `PhysxTendonAxisAPI`_ schema applied on it), then the joint
drive schema is not applied.
Based on the configuration, this method modifies the properties of the joint drive. These properties are
based on the `UsdPhysics.DriveAPI`_ schema. For more information on the properties, please refer to the
official documentation.
.. caution::
We highly recommend modifying joint properties of articulations through the functionalities in the
:mod:`omni.isaac.orbit.actuators` module. The methods here are for setting simulation low-level
properties only.
.. _UsdPhysics.DriveAPI: https://openusd.org/dev/api/class_usd_physics_drive_a_p_i.html
.. _PhysxTendonAxisAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_tendon_axis_a_p_i.html
Args:
prim_path: The prim path where to apply the joint drive schema.
drive_props: The configuration for the joint drive.
stage: The stage where to find the prim. Defaults to None, in which case the
current stage is used.
Returns:
True if the properties were successfully set, False otherwise.
Raises:
ValueError: If the input prim path is not valid.
"""
# obtain stage
if stage is None:
stage = stage_utils.get_current_stage()
# get USD prim
prim = stage.GetPrimAtPath(prim_path)
# check if prim path is valid
if not prim.IsValid():
raise ValueError(f"Prim path '{prim_path}' is not valid.")
# check if prim has joint drive applied on it
if prim.IsA(UsdPhysics.RevoluteJoint):
drive_api_name = "angular"
elif prim.IsA(UsdPhysics.PrismaticJoint):
drive_api_name = "linear"
else:
return False
# check that prim is not a tendon child prim
# note: root prim is what "controls" the tendon so we still want to apply the drive to it
if prim.HasAPI(PhysxSchema.PhysxTendonAxisAPI) and not prim.HasAPI(PhysxSchema.PhysxTendonAxisRootAPI):
return False
# check if prim has joint drive applied on it
usd_drive_api = UsdPhysics.DriveAPI(prim, drive_api_name)
if not usd_drive_api:
usd_drive_api = UsdPhysics.DriveAPI.Apply(prim, drive_api_name)
# change the drive type to input
if drive_props.drive_type is not None:
usd_drive_api.CreateTypeAttr().Set(drive_props.drive_type)
return True
"""
Fixed tendon properties.
"""
@apply_nested
def modify_fixed_tendon_properties(
prim_path: str, cfg: schemas_cfg.FixedTendonPropertiesCfg, stage: Usd.Stage | None = None
) -> bool:
"""Modify PhysX parameters for a fixed tendon attachment prim.
A `fixed tendon`_ can be used to link multiple degrees of freedom of articulation joints
through length and limit constraints. For instance, it can be used to set up an equality constraint
between a driven and passive revolute joints.
The schema comprises of attributes that belong to the `PhysxTendonAxisRootAPI`_ schema.
.. note::
This function is decorated with :func:`apply_nested` that sets the properties to all the prims
(that have the schema applied on them) under the input prim path.
.. _fixed tendon: https://nvidia-omniverse.github.io/PhysX/physx/5.3.1/_api_build/class_px_articulation_fixed_tendon.html
.. _PhysxTendonAxisRootAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_tendon_axis_root_a_p_i.html
Args:
prim_path: The prim path to the tendon attachment.
cfg: The configuration for the tendon attachment.
stage: The stage where to find the prim. Defaults to None, in which case the
current stage is used.
Returns:
True if the properties were successfully set, False otherwise.
Raises:
ValueError: If the input prim path is not valid.
"""
# obtain stage
if stage is None:
stage = stage_utils.get_current_stage()
# get USD prim
tendon_prim = stage.GetPrimAtPath(prim_path)
# check if prim has fixed tendon applied on it
has_root_fixed_tendon = tendon_prim.HasAPI(PhysxSchema.PhysxTendonAxisRootAPI)
if not has_root_fixed_tendon:
return False
# resolve all available instances of the schema since it is multi-instance
for schema_name in tendon_prim.GetAppliedSchemas():
# only consider the fixed tendon schema
if "PhysxTendonAxisRootAPI" not in schema_name:
continue
# retrieve the USD tendon api
instance_name = schema_name.split(":")[-1]
physx_tendon_axis_api = PhysxSchema.PhysxTendonAxisRootAPI(tendon_prim, instance_name)
# convert to dict
cfg = cfg.to_dict()
# set into PhysX API
for attr_name, value in cfg.items():
safe_set_attribute_on_usd_schema(physx_tendon_axis_api, attr_name, value, camel_case=True)
# success
return True
......@@ -5,6 +5,8 @@
from __future__ import annotations
from typing import Literal
from omni.isaac.orbit.utils import configclass
......@@ -142,3 +144,51 @@ class MassPropertiesCfg:
The density indirectly defines the mass of the rigid body. It is generally computed using the collision
approximation of the body.
"""
@configclass
class JointDrivePropertiesCfg:
"""Properties to define the drive mechanism of a joint.
See :meth:`modify_joint_drive_properties` for more information.
.. note::
If the values are None, they are not modified. This is useful when you want to set only a subset of
the properties and leave the rest as-is.
"""
drive_type: Literal["force", "acceleration"] | None = None
"""Joint drive type to apply.
If the drive type is "force", then the joint is driven by a force. If the drive type is "acceleration",
then the joint is driven by an acceleration (usually used for kinematic joints).
"""
@configclass
class FixedTendonPropertiesCfg:
"""Properties to define fixed tendons of an articulation.
See :meth:`modify_fixed_tendon_properties` for more information.
.. note::
If the values are None, they are not modified. This is useful when you want to set only a subset of
the properties and leave the rest as-is.
"""
tendon_enabled: bool | None = None
"""Whether to enable or disable the tendon."""
stiffness: float | None = None
"""Spring stiffness term acting on the tendon's length."""
damping: float | None = None
"""The damping term acting on both the tendon length and the tendon-length limits."""
limit_stiffness: float | None = None
"""Limit stiffness term acting on the tendon's length limits."""
offset: float | None = None
"""Length offset term for the tendon.
It defines an amount to be added to the accumulated length computed for the tendon. This allows the application
to actuate the tendon by shortening or lengthening it.
"""
rest_length: float | None = None
"""Spring rest length of the tendon."""
......@@ -243,6 +243,15 @@ def _spawn_from_usd_file(
# modify articulation root properties
if cfg.articulation_props is not None:
schemas.modify_articulation_root_properties(prim_path, cfg.articulation_props)
# modify tendon properties
if cfg.fixed_tendons_props is not None:
schemas.modify_fixed_tendon_properties(prim_path, cfg.fixed_tendons_props)
# define drive API on the joints
# note: these are only for setting low-level simulation properties. all others should be set or are
# and overridden by the articulation/actuator properties.
if cfg.joint_drive_props is not None:
schemas.modify_joint_drive_properties(prim_path, cfg.joint_drive_props)
# apply visual material
if cfg.visual_material is not None:
......
......@@ -32,6 +32,12 @@ class FileCfg(RigidObjectSpawnerCfg):
articulation_props: schemas.ArticulationPropertiesCfg | None = None
"""Properties to apply to the articulation root."""
fixed_tendons_props: schemas.FixedTendonsPropertiesCfg | None = None
"""Properties to apply to the fixed tendons (if any)."""
joint_drive_props: schemas.JointDrivePropertiesCfg | None = None
"""Properties to apply to a joint."""
visual_material_path: str = "material"
"""Path to the visual material to use for the prim. Defaults to "material".
......
......@@ -33,7 +33,7 @@ from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
##
# Pre-defined configs
##
from omni.isaac.orbit_assets import ANYMAL_C_CFG, FRANKA_PANDA_CFG # isort:skip
from omni.isaac.orbit_assets import ANYMAL_C_CFG, FRANKA_PANDA_CFG, SHADOW_HAND_CFG # isort:skip
class TestArticulation(unittest.TestCase):
......@@ -235,6 +235,39 @@ class TestArticulation(unittest.TestCase):
# update robot
robot.update(self.dt)
def test_initialization_hand_with_tendons(self):
"""Test initialization for fixed base articulated hand with tendons."""
# Create articulation
robot_cfg = SHADOW_HAND_CFG
robot = Articulation(cfg=robot_cfg.replace(prim_path="/World/Robot"))
# Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1)
# Play sim
self.sim.reset()
# Check if robot is initialized
self.assertTrue(robot._is_initialized)
# Check that fixed base
self.assertTrue(robot.is_fixed_base)
# Check buffers that exists and have correct shapes
self.assertTrue(robot.data.root_pos_w.shape == (1, 3))
self.assertTrue(robot.data.root_quat_w.shape == (1, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 24))
# Check some internal physx data for debugging
# -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count)
# -- link related
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count)
# Simulate physics
for _ in range(10):
# perform rendering
self.sim.step()
# update robot
robot.update(self.dt)
def test_out_of_range_default_joint_pos(self):
"""Test that the default joint position from configuration is out of range."""
# Create articulation
......
......@@ -71,6 +71,7 @@ class TestPhysicsSchema(unittest.TestCase):
torsional_patch_radius=1.0,
)
self.mass_cfg = schemas.MassPropertiesCfg(mass=1.0, density=100.0)
self.joint_cfg = schemas.JointDrivePropertiesCfg(drive_type="acceleration")
def tearDown(self) -> None:
"""Stops simulator after each test."""
......@@ -85,7 +86,7 @@ class TestPhysicsSchema(unittest.TestCase):
This is to ensure that we check that all the properties of the schema are set.
"""
for cfg in [self.arti_cfg, self.rigid_cfg, self.collision_cfg, self.mass_cfg]:
for cfg in [self.arti_cfg, self.rigid_cfg, self.collision_cfg, self.mass_cfg, self.joint_cfg]:
# check nothing is none
for k, v in cfg.__dict__.items():
self.assertIsNotNone(v, f"{cfg.__class__.__name__}:{k} is None. Please make sure schemas are valid.")
......@@ -109,10 +110,12 @@ class TestPhysicsSchema(unittest.TestCase):
schemas.modify_articulation_root_properties("/World/asset_instanced", self.arti_cfg)
schemas.modify_rigid_body_properties("/World/asset_instanced", self.rigid_cfg)
schemas.modify_mass_properties("/World/asset_instanced", self.mass_cfg)
schemas.modify_joint_drive_properties("/World/asset_instanced", self.joint_cfg)
# validate the properties
self._validate_properties_on_prim(
"/World/asset_instanced", ["PhysxArticulationRootAPI", "PhysxRigidBodyAPI", "PhysicsMassAPI"]
)
self._validate_articulation_properties_on_prim("/World/asset_instanced")
self._validate_rigid_body_properties_on_prim("/World/asset_instanced")
self._validate_mass_properties_on_prim("/World/asset_instanced")
self._validate_joint_drive_properties_on_prim("/World/asset_instanced")
def test_modify_properties_on_articulation_usd(self):
"""Test setting properties on articulation usd."""
......@@ -125,10 +128,13 @@ class TestPhysicsSchema(unittest.TestCase):
schemas.modify_rigid_body_properties("/World/asset", self.rigid_cfg)
schemas.modify_collision_properties("/World/asset", self.collision_cfg)
schemas.modify_mass_properties("/World/asset", self.mass_cfg)
schemas.modify_joint_drive_properties("/World/asset", self.joint_cfg)
# validate the properties
self._validate_properties_on_prim(
"/World/asset", ["PhysxArticulationAPI", "PhysxRigidBodyAPI", "PhysxCollisionAPI", "PhysicsMassAPI"]
)
self._validate_articulation_properties_on_prim("/World/asset")
self._validate_rigid_body_properties_on_prim("/World/asset")
self._validate_collision_properties_on_prim("/World/asset")
self._validate_mass_properties_on_prim("/World/asset")
self._validate_joint_drive_properties_on_prim("/World/asset")
def test_defining_rigid_body_properties_on_prim(self):
"""Test defining rigid body properties on a prim."""
......@@ -141,7 +147,9 @@ class TestPhysicsSchema(unittest.TestCase):
schemas.define_collision_properties("/World/cube1", self.collision_cfg)
schemas.define_mass_properties("/World/cube1", self.mass_cfg)
# validate the properties
self._validate_properties_on_prim("/World/cube1", ["PhysxRigidBodyAPI", "PhysxCollisionAPI", "PhysicsMassAPI"])
self._validate_rigid_body_properties_on_prim("/World/cube1")
self._validate_collision_properties_on_prim("/World/cube1")
self._validate_mass_properties_on_prim("/World/cube1")
# spawn another prim
prim_utils.create_prim("/World/cube2", prim_type="Cube", translation=(1.0, 1.0, 0.62))
......@@ -149,7 +157,8 @@ class TestPhysicsSchema(unittest.TestCase):
schemas.define_rigid_body_properties("/World/cube2", self.rigid_cfg)
schemas.define_collision_properties("/World/cube2", self.collision_cfg)
# validate the properties
self._validate_properties_on_prim("/World/cube2", ["PhysxRigidBodyAPI", "PhysxCollisionAPI"])
self._validate_rigid_body_properties_on_prim("/World/cube2")
self._validate_collision_properties_on_prim("/World/cube2")
# check if we can play
self.sim.reset()
......@@ -162,7 +171,8 @@ class TestPhysicsSchema(unittest.TestCase):
prim_utils.create_prim("/World/parent", prim_type="Xform")
schemas.define_articulation_root_properties("/World/parent", self.arti_cfg)
# validate the properties
self._validate_properties_on_prim("/World/parent", ["PhysxArticulationRootAPI"])
self._validate_articulation_properties_on_prim("/World/parent")
# create a child articulation
prim_utils.create_prim("/World/parent/child", prim_type="Cube", translation=(0.0, 0.0, 0.62))
schemas.define_rigid_body_properties("/World/parent/child", self.rigid_cfg)
......@@ -177,96 +187,143 @@ class TestPhysicsSchema(unittest.TestCase):
Helper functions.
"""
def _validate_properties_on_prim(self, prim_path: str, schema_names: list[str], verbose: bool = False):
"""Validate the properties on the prim.
def _validate_articulation_properties_on_prim(self, prim_path: str, verbose: bool = False):
"""Validate the articulation properties on the prim."""
# the root prim
root_prim = prim_utils.get_prim_at_path(prim_path)
# check articulation properties are set correctly
for attr_name, attr_value in self.arti_cfg.__dict__.items():
# skip names we know are not present
if attr_name == "func":
continue
# convert attribute name in prim to cfg name
prim_prop_name = f"physxArticulation:{to_camel_case(attr_name, to='cC')}"
# validate the values
self.assertAlmostEqual(
root_prim.GetAttribute(prim_prop_name).Get(),
attr_value,
places=5,
msg=f"Failed setting for {prim_prop_name}",
)
def _validate_rigid_body_properties_on_prim(self, prim_path: str, verbose: bool = False):
"""Validate the rigid body properties on the prim.
Note:
Right now this function exploits the hierarchy in the asset to check the properties. This is not a
fool-proof way of checking the properties. We should ideally check the properties on the prim itself
and all its children.
Args:
prim_path: The prim name.
schema_names: The list of schema names to validate.
verbose: Whether to print verbose logs. Defaults to False.
fool-proof way of checking the properties.
"""
# the root prim
root_prim = prim_utils.get_prim_at_path(prim_path)
# check articulation properties are set correctly
if "PhysxArticulationRootAPI" in schema_names:
for attr_name, attr_value in self.arti_cfg.__dict__.items():
# skip names we know are not present
if attr_name in ["func"]:
continue
# convert attribute name in prim to cfg name
prim_prop_name = f"physxArticulation:{to_camel_case(attr_name, to='cC')}"
# validate the values
self.assertAlmostEqual(
root_prim.GetAttribute(prim_prop_name).Get(),
attr_value,
places=5,
msg=f"Failed setting for {prim_prop_name}",
)
# check rigid body properties are set correctly
if "PhysxRigidBodyAPI" in schema_names:
for link_prim in root_prim.GetChildren():
if UsdPhysics.RigidBodyAPI(link_prim):
for attr_name, attr_value in self.rigid_cfg.__dict__.items():
for link_prim in root_prim.GetChildren():
if UsdPhysics.RigidBodyAPI(link_prim):
for attr_name, attr_value in self.rigid_cfg.__dict__.items():
# skip names we know are not present
if attr_name in ["func", "rigid_body_enabled", "kinematic_enabled"]:
continue
# convert attribute name in prim to cfg name
prim_prop_name = f"physxRigidBody:{to_camel_case(attr_name, to='cC')}"
# validate the values
self.assertAlmostEqual(
link_prim.GetAttribute(prim_prop_name).Get(),
attr_value,
places=5,
msg=f"Failed setting for {prim_prop_name}",
)
elif verbose:
print(f"Skipping prim {link_prim.GetPrimPath()} as it is not a rigid body.")
def _validate_collision_properties_on_prim(self, prim_path: str, verbose: bool = False):
"""Validate the collision properties on the prim.
Note:
Right now this function exploits the hierarchy in the asset to check the properties. This is not a
fool-proof way of checking the properties.
"""
# the root prim
root_prim = prim_utils.get_prim_at_path(prim_path)
# check collision properties are set correctly
for link_prim in root_prim.GetChildren():
for mesh_prim in link_prim.GetChildren():
if UsdPhysics.CollisionAPI(mesh_prim):
for attr_name, attr_value in self.collision_cfg.__dict__.items():
# skip names we know are not present
if attr_name in ["func", "rigid_body_enabled", "kinematic_enabled"]:
if attr_name in ["func", "collision_enabled"]:
continue
# convert attribute name in prim to cfg name
prim_prop_name = f"physxRigidBody:{to_camel_case(attr_name, to='cC')}"
prim_prop_name = f"physxCollision:{to_camel_case(attr_name, to='cC')}"
# validate the values
self.assertAlmostEqual(
link_prim.GetAttribute(prim_prop_name).Get(),
mesh_prim.GetAttribute(prim_prop_name).Get(),
attr_value,
places=5,
msg=f"Failed setting for {prim_prop_name}",
)
elif verbose:
print(f"Skipping prim {link_prim.GetPrimPath()} as it is not a rigid body.")
# check collision properties are set correctly
# note: we exploit the hierarchy in the asset to check
if "PhysxCollisionAPI" in schema_names:
for link_prim in root_prim.GetChildren():
for mesh_prim in link_prim.GetChildren():
if UsdPhysics.CollisionAPI(mesh_prim):
for attr_name, attr_value in self.collision_cfg.__dict__.items():
# skip names we know are not present
if attr_name in ["func", "collision_enabled"]:
continue
# convert attribute name in prim to cfg name
prim_prop_name = f"physxCollision:{to_camel_case(attr_name, to='cC')}"
# validate the values
self.assertAlmostEqual(
mesh_prim.GetAttribute(prim_prop_name).Get(),
attr_value,
places=5,
msg=f"Failed setting for {prim_prop_name}",
)
elif verbose:
print(f"Skipping prim {mesh_prim.GetPrimPath()} as it is not a collision mesh.")
print(f"Skipping prim {mesh_prim.GetPrimPath()} as it is not a collision mesh.")
def _validate_mass_properties_on_prim(self, prim_path: str, verbose: bool = False):
"""Validate the mass properties on the prim.
Note:
Right now this function exploits the hierarchy in the asset to check the properties. This is not a
fool-proof way of checking the properties.
"""
# the root prim
root_prim = prim_utils.get_prim_at_path(prim_path)
# check rigid body mass properties are set correctly
# note: we exploit the hierarchy in the asset to check
if "PhysicsMassAPI" in schema_names:
for link_prim in root_prim.GetChildren():
if UsdPhysics.MassAPI(link_prim):
for attr_name, attr_value in self.mass_cfg.__dict__.items():
for link_prim in root_prim.GetChildren():
if UsdPhysics.MassAPI(link_prim):
for attr_name, attr_value in self.mass_cfg.__dict__.items():
# skip names we know are not present
if attr_name in ["func"]:
continue
# print(link_prim.GetProperties())
prim_prop_name = f"physics:{to_camel_case(attr_name, to='cC')}"
# validate the values
self.assertAlmostEqual(
link_prim.GetAttribute(prim_prop_name).Get(),
attr_value,
places=5,
msg=f"Failed setting for {prim_prop_name}",
)
elif verbose:
print(f"Skipping prim {link_prim.GetPrimPath()} as it is not a mass api.")
def _validate_joint_drive_properties_on_prim(self, prim_path: str, verbose: bool = False):
"""Validate the mass properties on the prim.
Note:
Right now this function exploits the hierarchy in the asset to check the properties. This is not a
fool-proof way of checking the properties.
"""
# the root prim
root_prim = prim_utils.get_prim_at_path(prim_path)
# check joint drive properties are set correctly
for link_prim in root_prim.GetAllChildren():
for joint_prim in link_prim.GetChildren():
if joint_prim.IsA(UsdPhysics.PrismaticJoint) or joint_prim.IsA(UsdPhysics.RevoluteJoint):
# check it has drive API
self.assertTrue(joint_prim.HasAPI(UsdPhysics.DriveAPI))
# iterate over the joint properties
for attr_name, attr_value in self.joint_cfg.__dict__.items():
# skip names we know are not present
if attr_name in ["func"]:
if attr_name == "func":
continue
# manually check joint type
if attr_name == "drive_type":
if joint_prim.IsA(UsdPhysics.PrismaticJoint):
prim_attr_name = "drive:linear:physics:type"
elif joint_prim.IsA(UsdPhysics.RevoluteJoint):
prim_attr_name = "drive:angular:physics:type"
else:
raise ValueError(f"Unknown joint type for prim {joint_prim.GetPrimPath()}")
# check the value
self.assertEqual(attr_value, joint_prim.GetAttribute(prim_attr_name).Get())
continue
# print(link_prim.GetProperties())
prim_prop_name = f"physics:{to_camel_case(attr_name, to='cC')}"
# validate the values
self.assertAlmostEqual(
link_prim.GetAttribute(prim_prop_name).Get(),
attr_value,
places=5,
msg=f"Failed setting for {prim_prop_name}",
)
elif verbose:
print(f"Skipping prim {link_prim.GetPrimPath()} as it is not a mass api.")
print(f"Skipping prim {joint_prim.GetPrimPath()} as it is not a joint drive api.")
if __name__ == "__main__":
......
[package]
# Semantic Versioning is used: https://semver.org/
version = "0.1.0"
version = "0.1.1"
# Description
title = "ORBIT Assets"
......
Changelog
---------
0.1.1 (2024-03-11)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added configurations for allegro and shadow hand assets.
0.1.0 (2023-12-20)
~~~~~~~~~~~~~~~~~~
......
......@@ -31,9 +31,11 @@ __version__ = ORBIT_ASSETS_METADATA["package"]["version"]
# Configuration for different assets.
##
from .allegro import *
from .anymal import *
from .cartpole import *
from .franka import *
from .ridgeback_franka import *
from .shadow_hand import *
from .unitree import *
from .universal_robots import *
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the Allegro Hand robots from Wonik Robotics.
The following configurations are available:
* :obj:`ALLEGRO_HAND_CFG`: Allegro Hand with implicit actuator model.
Reference:
* https://www.wonikrobotics.com/robot-hand
"""
from __future__ import annotations
import math
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.actuators.actuator_cfg import ImplicitActuatorCfg
from omni.isaac.orbit.assets.articulation import ArticulationCfg
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
##
# Configuration
##
ALLEGRO_HAND_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/AllegroHand/allegro_hand_instanceable.usd",
activate_contact_sensors=False,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
retain_accelerations=False,
enable_gyroscopic_forces=False,
angular_damping=0.01,
max_linear_velocity=1000.0,
max_angular_velocity=64 / math.pi * 180.0,
max_depenetration_velocity=1000.0,
max_contact_impulse=1e32,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
solver_position_iteration_count=8,
solver_velocity_iteration_count=0,
sleep_threshold=0.005,
stabilization_threshold=0.0005,
),
# collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.5),
rot=(0.257551, 0.283045, 0.683330, -0.621782),
joint_pos={"^(?!thumb_joint_0).*": 0.0, "thumb_joint_0": 0.28},
),
actuators={
"fingers": ImplicitActuatorCfg(
joint_names_expr=[".*"],
effort_limit=0.5,
velocity_limit=100.0,
stiffness=3.0,
damping=0.1,
friction=0.01,
),
},
soft_joint_pos_limit_factor=1.0,
)
"""Configuration of Allegro Hand robot."""
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the dexterous hand from Shadow Robot.
The following configurations are available:
* :obj:`SHADOW_HAND_CFG`: Shadow Hand with implicit actuator model.
Reference:
* https://www.shadowrobot.com/dexterous-hand-series/
"""
from __future__ import annotations
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.actuators.actuator_cfg import ImplicitActuatorCfg
from omni.isaac.orbit.assets.articulation import ArticulationCfg
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
##
# Configuration
##
SHADOW_HAND_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ShadowHand/shadow_hand_instanceable.usd",
activate_contact_sensors=False,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
retain_accelerations=True,
max_depenetration_velocity=1000.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
solver_position_iteration_count=8,
solver_velocity_iteration_count=0,
sleep_threshold=0.005,
stabilization_threshold=0.0005,
),
# collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
joint_drive_props=sim_utils.JointDrivePropertiesCfg(drive_type="force"),
fixed_tendons_props=sim_utils.FixedTendonPropertiesCfg(limit_stiffness=30.0, damping=0.1),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.5),
rot=(0.0, 0.0, -0.7071, 0.7071),
joint_pos={".*": 0.0},
),
actuators={
"fingers": ImplicitActuatorCfg(
joint_names_expr=["robot0_WR.*", "robot0_(FF|MF|RF|LF|TH)J(3|2|1)", "robot0_(LF|TH)J4", "robot0_THJ0"],
effort_limit={
"robot0_WRJ1": 4.785,
"robot0_WRJ0": 2.175,
"robot0_(FF|MF|RF|LF)J1": 0.7245,
"robot0_FFJ(3|2)": 0.9,
"robot0_MFJ(3|2)": 0.9,
"robot0_RFJ(3|2)": 0.9,
"robot0_LFJ(4|3|2)": 0.9,
"robot0_THJ4": 2.3722,
"robot0_THJ3": 1.45,
"robot0_THJ(2|1)": 0.99,
"robot0_THJ0": 0.81,
},
stiffness={
"robot0_WRJ.*": 5.0,
"robot0_(FF|MF|RF|LF|TH)J(3|2|1)": 1.0,
"robot0_(LF|TH)J4": 1.0,
"robot0_THJ0": 1.0,
},
damping={
"robot0_WRJ.*": 0.5,
"robot0_(FF|MF|RF|LF|TH)J(3|2|1)": 0.1,
"robot0_(LF|TH)J4": 0.1,
"robot0_THJ0": 0.1,
},
),
},
soft_joint_pos_limit_factor=1.0,
)
"""Configuration of Shadow Hand robot."""
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script demonstrates different dexterous hands.
.. code-block:: bash
# Usage
./orbit.sh -p source/standalone/demos/hands.py
"""
from __future__ import annotations
"""Launch Isaac Sim Simulator first."""
import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="This script demonstrates different dexterous hands.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()
# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app
"""Rest everything follows."""
import numpy as np
import torch
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.assets import Articulation
##
# Pre-defined configs
##
from omni.isaac.orbit_assets.allegro import ALLEGRO_HAND_CFG # isort:skip
from omni.isaac.orbit_assets.shadow_hand import SHADOW_HAND_CFG # isort:skip
def define_origins(num_origins: int, spacing: float) -> list[list[float]]:
"""Defines the origins of the the scene."""
# create tensor based on number of environments
env_origins = torch.zeros(num_origins, 3)
# create a grid of origins
num_cols = np.floor(np.sqrt(num_origins))
num_rows = np.ceil(num_origins / num_cols)
xx, yy = torch.meshgrid(torch.arange(num_rows), torch.arange(num_cols), indexing="xy")
env_origins[:, 0] = spacing * xx.flatten()[:num_origins] - spacing * (num_rows - 1) / 2
env_origins[:, 1] = spacing * yy.flatten()[:num_origins] - spacing * (num_cols - 1) / 2
env_origins[:, 2] = 0.0
# return the origins
return env_origins.tolist()
def design_scene() -> tuple[dict, list[list[float]]]:
"""Designs the scene."""
# Ground-plane
cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg)
# Lights
cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.75, 0.75, 0.75))
cfg.func("/World/Light", cfg)
# Create separate groups called "Origin1", "Origin2", "Origin3"
# Each group will have a mount and a robot on top of it
origins = define_origins(num_origins=2, spacing=0.5)
# Origin 1 with Allegro Hand
prim_utils.create_prim("/World/Origin1", "Xform", translation=origins[0])
# -- Robot
allegro = Articulation(ALLEGRO_HAND_CFG.replace(prim_path="/World/Origin1/Robot"))
# Origin 2 with Shadow Hand
prim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1])
# -- Robot
shadow_hand = Articulation(SHADOW_HAND_CFG.replace(prim_path="/World/Origin2/Robot"))
# return the scene information
scene_entities = {
"allegro": allegro,
"shadow_hand": shadow_hand,
}
return scene_entities, origins
def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articulation], origins: torch.Tensor):
"""Runs the simulation loop."""
# Define simulation stepping
sim_dt = sim.get_physics_dt()
sim_time = 0.0
count = 0
# Start with hand open
grasp_mode = 0
# Simulate physics
while simulation_app.is_running():
# reset
if count % 1000 == 0:
# reset counters
sim_time = 0.0
count = 0
# reset robots
for index, robot in enumerate(entities.values()):
# root state
root_state = robot.data.default_root_state.clone()
root_state[:, :3] += origins[index]
robot.write_root_state_to_sim(root_state)
# joint state
joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone()
robot.write_joint_state_to_sim(joint_pos, joint_vel)
# reset the internal state
robot.reset()
print("[INFO]: Resetting robots state...")
# toggle grasp mode
if count % 100 == 0:
grasp_mode = 1 - grasp_mode
# apply default actions to the hands robots
for robot in entities.values():
# generate joint positions
joint_pos_target = robot.data.soft_joint_pos_limits[..., grasp_mode]
# apply action to the robot
robot.set_joint_position_target(joint_pos_target)
# write data to sim
robot.write_data_to_sim()
# perform step
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
# update buffers
for robot in entities.values():
robot.update(sim_dt)
def main():
"""Main function."""
# Initialize the simulation context
sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, substeps=1))
# Set main camera
sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5])
# design scene
scene_entities, scene_origins = design_scene()
scene_origins = torch.tensor(scene_origins, device=sim.device)
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Run the simulator
run_simulator(sim, scene_entities, scene_origins)
if __name__ == "__main__":
# run the main execution
main()
# 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