Unverified Commit 2ae4b2d8 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Adds `fix_root_link` attribute to ArticulationRootPropertiesCfg (#517)

# Description

This MR adds an attribute to fix the root link of an articulation. It
also fixes the docstrings to mention how to fix a rigid body in the
scene.

Fixes https://github.com/NVIDIA-Omniverse/orbit/issues/181,
https://github.com/NVIDIA-Omniverse/orbit/issues/365

## Type of change

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

## 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 0f52eaa7
...@@ -15,6 +15,7 @@ use Orbit. If you are new to Orbit, we recommend you start with the tutorials. ...@@ -15,6 +15,7 @@ use Orbit. If you are new to Orbit, we recommend you start with the tutorials.
import_new_asset import_new_asset
write_articulation_cfg write_articulation_cfg
make_fixed_prim
save_camera_output save_camera_output
draw_markers draw_markers
wrap_rl_env wrap_rl_env
......
Making a physics prim fixed in the simulation
=============================================
.. currentmodule:: omni.isaac.orbit
When a USD prim has physics schemas applied on it, it is affected by physics simulation.
This means that the prim can move, rotate, and collide with other prims in the simulation world.
However, there are cases where it is desirable to make certain prims static in the simulation world,
i.e. the prim should still participate in collisions but its position and orientation should not change.
The following sections describe how to spawn a prim with physics schemas and make it static in the simulation world.
Static colliders
----------------
Static colliders are prims that are not affected by physics but can collide with other prims in the simulation world.
These don't have any rigid body properties applied on them. However, this also means that they can't be accessed
using the physics tensor API (i.e., through the :class:`assets.RigidObject` class).
For instance, to spawn a cone static in the simulation world, the following code can be used:
.. code-block:: python
import omni.isaac.orbit.sim as sim_utils
cone_spawn_cfg = sim_utils.ConeCfg(
radius=0.15,
height=0.5,
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0)),
)
cone_spawn_cfg.func(
"/World/Cone", cone_spawn_cfg, translation=(0.0, 0.0, 2.0), orientation=(0.5, 0.0, 0.5, 0.0)
)
Rigid object
------------
Rigid objects (i.e. object only has a single body) can be made static by setting the parameter
:attr:`sim.schemas.RigidBodyPropertiesCfg.kinematic_enabled` as True. This will make the object
kinematic and it will not be affected by physics.
For instance, to spawn a cone static in the simulation world but with rigid body schema on it,
the following code can be used:
.. code-block:: python
import omni.isaac.orbit.sim as sim_utils
cone_spawn_cfg = sim_utils.ConeCfg(
radius=0.15,
height=0.5,
rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True),
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0)),
)
cone_spawn_cfg.func(
"/World/Cone", cone_spawn_cfg, translation=(0.0, 0.0, 2.0), orientation=(0.5, 0.0, 0.5, 0.0)
)
Articulation
------------
Fixing the root of an articulation requires having a fixed joint to the root rigid body link of the articulation.
This can be achieved by setting the parameter :attr:`sim.schemas.ArticulationRootPropertiesCfg.fix_root_link`
as True. Based on the value of this parameter, the following cases are possible:
* If set to :obj:`None`, the root link is not modified.
* If the articulation already has a fixed root link, this flag will enable or disable the fixed joint.
* If the articulation does not have a fixed root link, this flag will create a fixed joint between the world
frame and the root link. The joint is created with the name "FixedJoint" under the root link.
For instance, to spawn an ANYmal robot and make it static in the simulation world, the following code can be used:
.. code-block:: python
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.utils.assets import ISAAC_ORBIT_NUCLEUS_DIR
anymal_spawn_cfg = sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
solver_position_iteration_count=4,
solver_velocity_iteration_count=0,
fix_root_link=True,
),
)
anymal_spawn_cfg.func(
"/World/ANYmal", anymal_spawn_cfg, translation=(0.0, 0.0, 0.8), orientation=(1.0, 0.0, 0.0, 0.0)
)
This will create a fixed joint between the world frame and the root link of the ANYmal robot
at the prim path ``"/World/ANYmal/base/FixedJoint"`` since the root link is at the path ``"/World/ANYmal/base"``.
Further notes
-------------
Given the flexibility of USD asset designing the following possible scenarios are usually encountered:
1. **Articulation root schema on the rigid body prim without a fixed joint**:
This is the most common and recommended scenario for floating-base articulations. The root prim
has both the rigid body and the articulation root properties. In this case, the articulation root
is parsed as a floating-base with the root prim of the articulation ``Link0Xform``.
.. code-block:: text
ArticulationXform
└── Link0Xform (RigidBody and ArticulationRoot schema)
2. **Articulation root schema on the parent prim with a fixed joint**:
This is the expected arrangement for fixed-base articulations. The root prim has only the rigid body
properties and the articulation root properties are applied to its parent prim. In this case, the
articulation root is parsed as a fixed-base with the root prim of the articulation ``Link0Xform``.
.. code-block:: text
ArticulationXform (ArticulationRoot schema)
└── Link0Xform (RigidBody schema)
└── FixedJoint (connecting the world frame and Link0Xform)
3. **Articulation root schema on the parent prim without a fixed joint**:
This is a scenario where the root prim has only the rigid body properties and the articulation root properties
are applied to its parent prim. However, the fixed joint is not created between the world frame and the root link.
In this case, the articulation is parsed as a floating-base system. However, the PhysX parser uses its own
heuristic (such as alphabetical order) to determine the root prim of the articulation. It may select the root prim
at ``Link0Xform`` or choose another prim as the root prim.
.. code-block:: text
ArticulationXform (ArticulationRoot schema)
└── Link0Xform (RigidBody schema)
4. **Articulation root schema on the rigid body prim with a fixed joint**:
While this is a valid scenario, it is not recommended as it may lead to unexpected behavior. In this case,
the articulation is still parsed as a floating-base system. However, the fixed joint, created between the
world frame and the root link, is considered as a part of the maximal coordinate tree. This is different from
PhysX considering the articulation as a fixed-base system. Hence, the simulation may not behave as expected.
.. code-block:: text
ArticulationXform
└── Link0Xform (RigidBody and ArticulationRoot schema)
└── FixedJoint (connecting the world frame and Link0Xform)
For floating base articulations, the root prim usually has both the rigid body and the articulation
root properties. However, directly connecting this prim to the world frame will cause the simulation
to consider the fixed joint as a part of the maximal coordinate tree. This is different from PhysX
considering the articulation as a fixed-base system.
Internally, when the parameter :attr:`sim.schemas.ArticulationRootPropertiesCfg.fix_root_link` is set to True
and the articulation is detected as a floating-base system, the fixed joint is created between the world frame
the root rigid body link of the articulation. However, to make the PhysX parser consider the articulation as a
fixed-base system, the articulation root properties are removed from the root rigid body prim and applied to
its parent prim instead.
.. note::
In future release of Isaac Sim, an explicit flag will be added to the articulation root schema from PhysX
to toggle between fixed-base and floating-base systems. This will resolve the need of the above workaround.
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.16.0" version = "0.16.1"
# Description # Description
title = "ORBIT framework for Robot Learning" title = "ORBIT framework for Robot Learning"
......
Changelog Changelog
--------- ---------
0.16.1 (2024-04-20)
~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added attribute :attr:`omni.isaac.orbit.sim.ArticulationRootPropertiesCfg.fix_root_link` to fix the root link
of an articulation to the world frame.
0.16.0 (2024-04-16) 0.16.0 (2024-04-16)
~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~
......
...@@ -8,9 +8,10 @@ from __future__ import annotations ...@@ -8,9 +8,10 @@ from __future__ import annotations
import carb import carb
import omni.isaac.core.utils.stage as stage_utils import omni.isaac.core.utils.stage as stage_utils
import omni.physx.scripts.utils as physx_utils
from pxr import PhysxSchema, Usd, UsdPhysics from pxr import PhysxSchema, Usd, UsdPhysics
from ..utils import apply_nested, safe_set_attribute_on_usd_schema from ..utils import apply_nested, find_global_fixed_joint_prim, safe_set_attribute_on_usd_schema
from . import schemas_cfg from . import schemas_cfg
""" """
...@@ -67,6 +68,12 @@ def modify_articulation_root_properties( ...@@ -67,6 +68,12 @@ def modify_articulation_root_properties(
and velocity iteration counts, sleep threshold, stabilization threshold) take precedence over those specified and velocity iteration counts, sleep threshold, stabilization threshold) take precedence over those specified
in the rigid body schemas for all the rigid bodies in the articulation. in the rigid body schemas for all the rigid bodies in the articulation.
.. caution::
When the attribute :attr:`schemas_cfg.ArticulationRootPropertiesCfg.fix_root_link` is set to True,
a fixed joint is created between the root link and the world frame (if it does not already exist). However,
to deal with physics parser limitations, the articulation root schema needs to be applied to the parent of
the root link.
.. note:: .. note::
This function is decorated with :func:`apply_nested` that set the properties to all the prims This function is decorated with :func:`apply_nested` that set the properties to all the prims
(that have the schema applied on them) under the input prim path. (that have the schema applied on them) under the input prim path.
...@@ -83,6 +90,9 @@ def modify_articulation_root_properties( ...@@ -83,6 +90,9 @@ def modify_articulation_root_properties(
Returns: Returns:
True if the properties were successfully set, False otherwise. True if the properties were successfully set, False otherwise.
Raises:
NotImplementedError: When the root prim is not a rigid body and a fixed joint is to be created.
""" """
# obtain stage # obtain stage
if stage is None: if stage is None:
...@@ -99,9 +109,67 @@ def modify_articulation_root_properties( ...@@ -99,9 +109,67 @@ def modify_articulation_root_properties(
# convert to dict # convert to dict
cfg = cfg.to_dict() cfg = cfg.to_dict()
# extract non-USD properties
fix_root_link = cfg.pop("fix_root_link", None)
# set into physx api # set into physx api
for attr_name, value in cfg.items(): for attr_name, value in cfg.items():
safe_set_attribute_on_usd_schema(physx_articulation_api, attr_name, value, camel_case=True) safe_set_attribute_on_usd_schema(physx_articulation_api, attr_name, value, camel_case=True)
# fix root link based on input
# we do the fixed joint processing later to not interfere with setting other properties
if fix_root_link is not None:
# check if a global fixed joint exists under the root prim
existing_fixed_joint_prim = find_global_fixed_joint_prim(prim_path)
# if we found a fixed joint, enable/disable it based on the input
# otherwise, create a fixed joint between the world and the root link
if existing_fixed_joint_prim is not None:
carb.log_info(
f"Found an existing fixed joint for the articulation: '{prim_path}'. Setting it to: {fix_root_link}."
)
existing_fixed_joint_prim.GetJointEnabledAttr().Set(fix_root_link)
elif fix_root_link:
carb.log_info(f"Creating a fixed joint for the articulation: '{prim_path}'.")
# note: we have to assume that the root prim is a rigid body,
# i.e. we don't handle the case where the root prim is not a rigid body but has articulation api on it
# Currently, there is no obvious way to get first rigid body link identified by the PhysX parser
if not articulation_prim.HasAPI(UsdPhysics.RigidBodyAPI):
raise NotImplementedError(
f"The articulation prim '{prim_path}' does not have the RigidBodyAPI applied."
" To create a fixed joint, we need to determine the first rigid body link in"
" the articulation tree. However, this is not implemented yet."
)
# create a fixed joint between the root link and the world frame
physx_utils.createJoint(stage=stage, joint_type="Fixed", from_prim=None, to_prim=articulation_prim)
# Having a fixed joint on a rigid body is not treated as "fixed base articulation".
# instead, it is treated as a part of the maximal coordinate tree.
# Moving the articulation root to the parent solves this issue. This is a limitation of the PhysX parser.
# get parent prim
parent_prim = articulation_prim.GetParent()
# apply api to parent
UsdPhysics.ArticulationRootAPI.Apply(parent_prim)
PhysxSchema.PhysxArticulationAPI.Apply(parent_prim)
# copy the attributes
# -- usd attributes
usd_articulation_api = UsdPhysics.ArticulationRootAPI(articulation_prim)
for attr_name in usd_articulation_api.GetSchemaAttributeNames():
attr = articulation_prim.GetAttribute(attr_name)
parent_prim.GetAttribute(attr_name).Set(attr.Get())
# -- physx attributes
physx_articulation_api = PhysxSchema.PhysxArticulationAPI(articulation_prim)
for attr_name in physx_articulation_api.GetSchemaAttributeNames():
attr = articulation_prim.GetAttribute(attr_name)
parent_prim.GetAttribute(attr_name).Set(attr.Get())
# remove api from root
articulation_prim.RemoveAPI(UsdPhysics.ArticulationRootAPI)
articulation_prim.RemoveAPI(PhysxSchema.PhysxArticulationAPI)
# success # success
return True return True
......
...@@ -31,6 +31,18 @@ class ArticulationRootPropertiesCfg: ...@@ -31,6 +31,18 @@ class ArticulationRootPropertiesCfg:
"""Mass-normalized kinetic energy threshold below which an actor may go to sleep.""" """Mass-normalized kinetic energy threshold below which an actor may go to sleep."""
stabilization_threshold: float | None = None stabilization_threshold: float | None = None
"""The mass-normalized kinetic energy threshold below which an articulation may participate in stabilization.""" """The mass-normalized kinetic energy threshold below which an articulation may participate in stabilization."""
fix_root_link: bool | None = None
"""Whether to fix the root link of the articulation.
* If set to None, the root link is not modified.
* If the articulation already has a fixed root link, this flag will enable or disable the fixed joint.
* If the articulation does not have a fixed root link, this flag will create a fixed joint between the world
frame and the root link. The joint is created with the name "FixedJoint" under the articulation prim.
.. note::
This is a non-USD schema property. It is handled by the :meth:`modify_articulation_root_properties` function.
"""
@configclass @configclass
......
...@@ -221,7 +221,7 @@ Helper functions. ...@@ -221,7 +221,7 @@ Helper functions.
def _spawn_geom_from_prim_type( def _spawn_geom_from_prim_type(
prim_path: str, prim_path: str,
cfg: shapes_cfg.GeometryCfg, cfg: shapes_cfg.ShapeCfg,
prim_type: str, prim_type: str,
attributes: dict, attributes: dict,
translation: tuple[float, float, float] | None = None, translation: tuple[float, float, float] | None = None,
......
...@@ -83,8 +83,14 @@ class RigidObjectSpawnerCfg(SpawnerCfg): ...@@ -83,8 +83,14 @@ class RigidObjectSpawnerCfg(SpawnerCfg):
mass_props: schemas.MassPropertiesCfg | None = None mass_props: schemas.MassPropertiesCfg | None = None
"""Mass properties.""" """Mass properties."""
rigid_props: schemas.RigidBodyPropertiesCfg | None = None rigid_props: schemas.RigidBodyPropertiesCfg | None = None
"""Rigid body properties.""" """Rigid body properties.
For making a rigid object static, set the :attr:`schemas.RigidBodyPropertiesCfg.kinematic_enabled`
as True. This will make the object static and will not be affected by gravity or other forces.
"""
collision_props: schemas.CollisionPropertiesCfg | None = None collision_props: schemas.CollisionPropertiesCfg | None = None
"""Properties to apply to all collision meshes.""" """Properties to apply to all collision meshes."""
......
...@@ -718,3 +718,62 @@ def find_matching_prim_paths(prim_path_regex: str, stage: Usd.Stage | None = Non ...@@ -718,3 +718,62 @@ def find_matching_prim_paths(prim_path_regex: str, stage: Usd.Stage | None = Non
for prim in output_prims: for prim in output_prims:
output_prim_paths.append(prim.GetPath().pathString) output_prim_paths.append(prim.GetPath().pathString)
return output_prim_paths return output_prim_paths
def find_global_fixed_joint_prim(
prim_path: str | Sdf.Path, check_enabled_only: bool = False, stage: Usd.Stage | None = None
) -> UsdPhysics.Joint | None:
"""Find the fixed joint prim under the specified prim path that connects the target to the simulation world.
A joint is a connection between two bodies. A fixed joint is a joint that does not allow relative motion
between the two bodies. When a fixed joint has only one target body, it is considered to attach the body
to the simulation world.
This function finds the fixed joint prim that has only one target under the specified prim path. If no such
fixed joint prim exists, it returns None.
Args:
prim_path: The prim path to search for the fixed joint prim.
check_enabled_only: Whether to consider only enabled fixed joints. Defaults to False.
If False, then all joints (enabled or disabled) are considered.
stage: The stage where the prim exists. Defaults to None, in which case the current stage is used.
Returns:
The fixed joint prim that has only one target. If no such fixed joint prim exists, it returns None.
Raises:
ValueError: If the prim path is not global (i.e: does not start with '/').
ValueError: If the prim path does not exist on the stage.
"""
# check prim path is global
if not prim_path.startswith("/"):
raise ValueError(f"Prim path '{prim_path}' is not global. It must start with '/'.")
# get current stage
if stage is None:
stage = stage_utils.get_current_stage()
# check if prim exists
prim = stage.GetPrimAtPath(prim_path)
if not prim.IsValid():
raise ValueError(f"Prim at path '{prim_path}' is not valid.")
fixed_joint_prim = None
# we check all joints under the root prim and classify the asset as fixed base if there exists
# a fixed joint that has only one target (i.e. the root link).
for prim in Usd.PrimRange(prim):
# note: ideally checking if it is FixedJoint would have been enough, but some assets use "Joint" as the
# schema name which makes it difficult to distinguish between the two.
joint_prim = UsdPhysics.Joint(prim)
if joint_prim:
# if check_enabled_only is True, we only consider enabled joints
if check_enabled_only and not joint_prim.GetJointEnabledAttr().Get():
continue
# check body 0 and body 1 exist
body_0_exist = joint_prim.GetBody0Rel().GetTargets() != []
body_1_exist = joint_prim.GetBody1Rel().GetTargets() != []
# if either body 0 or body 1 does not exist, we have a fixed joint that connects to the world
if not (body_0_exist and body_1_exist):
fixed_joint_prim = joint_prim
break
return fixed_joint_prim
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script demonstrates fixed-base API for different robots.
.. code-block:: bash
# Usage
./orbit.sh -p source/extensions/omni.isaac.orbit/test/assets/check_fixed_base_assets.py
"""
"""Launch Isaac Sim Simulator first."""
import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="This script checks the fixed-base API for different robots.")
# 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 import ANYMAL_C_CFG, FRANKA_PANDA_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=4, spacing=2.0)
# Origin 1 with Franka Panda
prim_utils.create_prim("/World/Origin1", "Xform", translation=origins[0])
# -- Robot
franka = Articulation(FRANKA_PANDA_CFG.replace(prim_path="/World/Origin1/Robot"))
# Origin 2 with Anymal C
prim_utils.create_prim("/World/Origin2", "Xform", translation=origins[1])
# -- Robot
robot_cfg = ANYMAL_C_CFG.replace(prim_path="/World/Origin2/Robot")
robot_cfg.spawn.articulation_props.fix_root_link = True
anymal_c = Articulation(robot_cfg)
# return the scene information
scene_entities = {
"franka": franka,
"anymal_c": anymal_c,
}
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
# Simulate physics
while simulation_app.is_running():
# reset
if count % 200 == 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]
root_state[:, :2] += torch.randn_like(root_state[:, :2]) * 0.25
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...")
# apply default actions to the quadrupedal robots
for name, robot in entities.items():
if count % 200 == 0:
print("Name: ", name, "is_fixed_base: ", robot.is_fixed_base)
# generate random joint positions
joint_pos_target = robot.data.default_joint_pos + torch.randn_like(robot.data.joint_pos) * 0.1
# 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=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# 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 function
main()
# close sim app
simulation_app.close()
...@@ -181,6 +181,9 @@ class TestArticulation(unittest.TestCase): ...@@ -181,6 +181,9 @@ class TestArticulation(unittest.TestCase):
self.sim.step() self.sim.step()
# update robot # update robot
robot.update(self.dt) robot.update(self.dt)
# check that the root is at the correct state
default_root_state = robot.data.default_root_state.clone()
torch.testing.assert_close(robot.data.root_state_w, default_root_state)
def test_initialization_fixed_base_single_joint(self): def test_initialization_fixed_base_single_joint(self):
"""Test initialization for fixed base articulation with a single joint.""" """Test initialization for fixed base articulation with a single joint."""
...@@ -266,6 +269,93 @@ class TestArticulation(unittest.TestCase): ...@@ -266,6 +269,93 @@ class TestArticulation(unittest.TestCase):
# update robot # update robot
robot.update(self.dt) robot.update(self.dt)
def test_initialization_floating_base_made_fixed_base(self):
"""Test initialization for a floating-base articulation made fixed-base using schema properties."""
# Create articulation
robot_cfg: ArticulationCfg = ANYMAL_C_CFG.replace(prim_path="/World/Robot")
robot_cfg.spawn.articulation_props.fix_root_link = True
robot = Articulation(cfg=robot_cfg)
# 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 floating 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, 12))
# 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)
# -- link names (check within articulation ordering is correct)
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]]
self.assertListEqual(prim_path_body_names, robot.body_names)
# Check that the body_physx_view is deprecated
with self.assertWarns(DeprecationWarning):
robot.body_physx_view
# Root state should be at the default state
robot.write_root_state_to_sim(robot.data.default_root_state.clone())
# Simulate physics
for _ in range(10):
# perform rendering
self.sim.step()
# update robot
robot.update(self.dt)
# check that the root is at the correct state
default_root_state = robot.data.default_root_state.clone()
torch.testing.assert_close(robot.data.root_state_w, default_root_state)
def test_initialization_fixed_base_made_floating_base(self):
"""Test initialization for fixed base made floating-base using schema properties."""
# Create articulation
robot_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/Robot")
robot_cfg.spawn.articulation_props.fix_root_link = False
robot = Articulation(cfg=robot_cfg)
# 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.assertFalse(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, 9))
# 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)
# -- link names (check within articulation ordering is correct)
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]]
self.assertListEqual(prim_path_body_names, robot.body_names)
# Simulate physics
for _ in range(10):
# perform rendering
self.sim.step()
# update robot
robot.update(self.dt)
# check that the root is at the correct state
default_root_state = robot.data.default_root_state.clone()
is_close = torch.any(torch.isclose(robot.data.root_state_w, default_root_state))
self.assertFalse(is_close)
def test_out_of_range_default_joint_pos(self): def test_out_of_range_default_joint_pos(self):
"""Test that the default joint position from configuration is out of range.""" """Test that the default joint position from configuration is out of range."""
# Create articulation # Create articulation
......
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""This script demonstrates how to make a floating robot fixed in Isaac Sim."""
"""Launch Isaac Sim Simulator first."""
import argparse
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser(
description="This script shows the issue in Isaac Sim with making a floating robot fixed."
)
parser.add_argument("--headless", action="store_true", help="Run in headless mode.")
parser.add_argument("--fix-base", action="store_true", help="Whether to fix the base of the robot.")
# parse the arguments
args_cli = parser.parse_args()
# launch omniverse app
simulation_app = SimulationApp({"headless": args_cli.headless})
"""Rest everything follows."""
import torch
import carb
import omni.isaac.core.utils.nucleus as nucleus_utils
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
import omni.kit.commands
import omni.physx
from omni.isaac.core.articulations import ArticulationView
from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view
from omni.isaac.core.world import World
from pxr import PhysxSchema, UsdPhysics
# check nucleus connection
if nucleus_utils.get_assets_root_path() is None:
msg = (
"Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n"
"\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus"
)
carb.log_error(msg)
raise RuntimeError(msg)
ISAAC_NUCLEUS_DIR = f"{nucleus_utils.get_assets_root_path()}/Isaac"
"""Path to the `Isaac` directory on the NVIDIA Nucleus Server."""
ISAAC_ORBIT_NUCLEUS_DIR = f"{nucleus_utils.get_assets_root_path()}/Isaac/Samples/Orbit"
"""Path to the `Isaac/Samples/Orbit` directory on the NVIDIA Nucleus Server."""
"""
Main
"""
def main():
"""Spawns the ANYmal robot and makes it fixed."""
# Load kit helper
world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu")
# Set main camera
set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Enable hydra scene-graph instancing
# this is needed to visualize the scene when flatcache is enabled
set_carb_setting(world._settings, "/persistent/omnihydra/useSceneGraphInstancing", True)
# Spawn things into stage
# Ground-plane
world.scene.add_default_ground_plane(prim_path="/World/defaultGroundPlane", z_position=0.0)
# Lights-1
prim_utils.create_prim("/World/Light/GreySphere", "SphereLight", translation=(4.5, 3.5, 10.0))
# Lights-2
prim_utils.create_prim("/World/Light/WhiteSphere", "SphereLight", translation=(-4.5, 3.5, 10.0))
# -- Robot
# resolve asset
usd_path = f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd"
root_prim_path = "/World/Robot/base"
# add asset
print("Loading robot from: ", usd_path)
prim_utils.create_prim(
"/World/Robot",
usd_path=usd_path,
translation=(0.0, 0.0, 0.6),
)
# create fixed joint
if args_cli.fix_base:
# get all necessary information
stage = stage_utils.get_current_stage()
root_prim = stage.GetPrimAtPath(root_prim_path)
parent_prim = root_prim.GetParent()
# here we assume that the root prim is a rigid body
# there is no clear way to deal with situation where the root prim is not a rigid body but has articulation api
# in that case, it is unclear how to get the link to the first link in the tree
if not root_prim.HasAPI(UsdPhysics.RigidBodyAPI):
raise RuntimeError("The root prim does not have the RigidBodyAPI applied.")
# create fixed joint
omni.kit.commands.execute(
"CreateJointCommand",
stage=stage,
joint_type="Fixed",
from_prim=None,
to_prim=root_prim,
)
# move the root to the parent if this is a rigid body
# having a fixed joint on a rigid body makes physx treat it as a part of the maximal coordinate tree
# if we put to joint on the parent, physx parser treats it as a fixed base articulation
# get parent prim
parent_prim = root_prim.GetParent()
# apply api to parent
UsdPhysics.ArticulationRootAPI.Apply(parent_prim)
PhysxSchema.PhysxArticulationAPI.Apply(parent_prim)
# copy the attributes
# -- usd attributes
root_usd_articulation_api = UsdPhysics.ArticulationRootAPI(root_prim)
for attr_name in root_usd_articulation_api.GetSchemaAttributeNames():
attr = root_prim.GetAttribute(attr_name)
parent_prim.GetAttribute(attr_name).Set(attr.Get())
# -- physx attributes
root_physx_articulation_api = PhysxSchema.PhysxArticulationAPI(root_prim)
for attr_name in root_physx_articulation_api.GetSchemaAttributeNames():
attr = root_prim.GetAttribute(attr_name)
parent_prim.GetAttribute(attr_name).Set(attr.Get())
# remove api from root
root_prim.RemoveAPI(UsdPhysics.ArticulationRootAPI)
root_prim.RemoveAPI(PhysxSchema.PhysxArticulationAPI)
# rename root path to parent path
root_prim_path = parent_prim.GetPath().pathString
# Setup robot
robot_view = ArticulationView(root_prim_path, name="ANYMAL")
world.scene.add(robot_view)
# Play the simulator
world.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# dummy actions
# actions = torch.zeros(robot.count, robot.num_actions, device=robot.device)
init_root_pos_w, init_root_quat_w = robot_view.get_world_poses()
# Define simulation stepping
sim_dt = world.get_physics_dt()
# episode counter
sim_time = 0.0
count = 0
# Simulate physics
while simulation_app.is_running():
# If simulation is stopped, then exit.
if world.is_stopped():
break
# If simulation is paused, then skip.
if not world.is_playing():
world.step(render=False)
continue
# do reset
if count % 20 == 0:
# reset
sim_time = 0.0
count = 0
# reset root state
root_pos_w = init_root_pos_w.clone()
root_pos_w[:, :2] += torch.rand_like(root_pos_w[:, :2]) * 0.5
robot_view.set_world_poses(root_pos_w, init_root_quat_w)
# print if it is fixed base
print("Fixed base: ", robot_view._physics_view.shared_metatype.fixed_base)
print("Moving base to: ", root_pos_w[0].cpu().numpy())
print("-" * 50)
# apply random joint actions
actions = torch.rand_like(robot_view.get_joint_positions()) * 0.001
robot_view.set_joint_efforts(actions)
# perform step
world.step()
# update sim-time
sim_time += sim_dt
count += 1
if __name__ == "__main__":
# run the main function
main()
# close sim app
simulation_app.close()
...@@ -20,6 +20,7 @@ from omni.isaac.core.simulation_context import SimulationContext ...@@ -20,6 +20,7 @@ from omni.isaac.core.simulation_context import SimulationContext
from pxr import UsdPhysics from pxr import UsdPhysics
import omni.isaac.orbit.sim.schemas as schemas import omni.isaac.orbit.sim.schemas as schemas
from omni.isaac.orbit.sim.utils import find_global_fixed_joint_prim
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
from omni.isaac.orbit.utils.string import to_camel_case from omni.isaac.orbit.utils.string import to_camel_case
...@@ -43,6 +44,7 @@ class TestPhysicsSchema(unittest.TestCase): ...@@ -43,6 +44,7 @@ class TestPhysicsSchema(unittest.TestCase):
solver_velocity_iteration_count=1, solver_velocity_iteration_count=1,
sleep_threshold=1.0, sleep_threshold=1.0,
stabilization_threshold=5.0, stabilization_threshold=5.0,
fix_root_link=False,
) )
self.rigid_cfg = schemas.RigidBodyPropertiesCfg( self.rigid_cfg = schemas.RigidBodyPropertiesCfg(
rigid_body_enabled=True, rigid_body_enabled=True,
...@@ -110,11 +112,17 @@ class TestPhysicsSchema(unittest.TestCase): ...@@ -110,11 +112,17 @@ class TestPhysicsSchema(unittest.TestCase):
schemas.modify_mass_properties("/World/asset_instanced", self.mass_cfg) schemas.modify_mass_properties("/World/asset_instanced", self.mass_cfg)
schemas.modify_joint_drive_properties("/World/asset_instanced", self.joint_cfg) schemas.modify_joint_drive_properties("/World/asset_instanced", self.joint_cfg)
# validate the properties # validate the properties
self._validate_articulation_properties_on_prim("/World/asset_instanced") self._validate_articulation_properties_on_prim("/World/asset_instanced", has_default_fixed_root=False)
self._validate_rigid_body_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_mass_properties_on_prim("/World/asset_instanced")
self._validate_joint_drive_properties_on_prim("/World/asset_instanced") self._validate_joint_drive_properties_on_prim("/World/asset_instanced")
# make a fixed joint
# note: for this asset, it doesn't work because the root is not a rigid body
self.arti_cfg.fix_root_link = True
with self.assertRaises(NotImplementedError):
schemas.modify_articulation_root_properties("/World/asset_instanced", self.arti_cfg)
def test_modify_properties_on_articulation_usd(self): def test_modify_properties_on_articulation_usd(self):
"""Test setting properties on articulation usd.""" """Test setting properties on articulation usd."""
# spawn asset to the stage # spawn asset to the stage
...@@ -128,12 +136,18 @@ class TestPhysicsSchema(unittest.TestCase): ...@@ -128,12 +136,18 @@ class TestPhysicsSchema(unittest.TestCase):
schemas.modify_mass_properties("/World/asset", self.mass_cfg) schemas.modify_mass_properties("/World/asset", self.mass_cfg)
schemas.modify_joint_drive_properties("/World/asset", self.joint_cfg) schemas.modify_joint_drive_properties("/World/asset", self.joint_cfg)
# validate the properties # validate the properties
self._validate_articulation_properties_on_prim("/World/asset") self._validate_articulation_properties_on_prim("/World/asset", has_default_fixed_root=True)
self._validate_rigid_body_properties_on_prim("/World/asset") self._validate_rigid_body_properties_on_prim("/World/asset")
self._validate_collision_properties_on_prim("/World/asset") self._validate_collision_properties_on_prim("/World/asset")
self._validate_mass_properties_on_prim("/World/asset") self._validate_mass_properties_on_prim("/World/asset")
self._validate_joint_drive_properties_on_prim("/World/asset") self._validate_joint_drive_properties_on_prim("/World/asset")
# make a fixed joint
self.arti_cfg.fix_root_link = True
schemas.modify_articulation_root_properties("/World/asset", self.arti_cfg)
# validate the properties
self._validate_articulation_properties_on_prim("/World/asset", has_default_fixed_root=True)
def test_defining_rigid_body_properties_on_prim(self): def test_defining_rigid_body_properties_on_prim(self):
"""Test defining rigid body properties on a prim.""" """Test defining rigid body properties on a prim."""
# create a prim # create a prim
...@@ -169,7 +183,7 @@ class TestPhysicsSchema(unittest.TestCase): ...@@ -169,7 +183,7 @@ class TestPhysicsSchema(unittest.TestCase):
prim_utils.create_prim("/World/parent", prim_type="Xform") prim_utils.create_prim("/World/parent", prim_type="Xform")
schemas.define_articulation_root_properties("/World/parent", self.arti_cfg) schemas.define_articulation_root_properties("/World/parent", self.arti_cfg)
# validate the properties # validate the properties
self._validate_articulation_properties_on_prim("/World/parent") self._validate_articulation_properties_on_prim("/World/parent", has_default_fixed_root=False)
# create a child articulation # create a child articulation
prim_utils.create_prim("/World/parent/child", prim_type="Cube", translation=(0.0, 0.0, 0.62)) prim_utils.create_prim("/World/parent/child", prim_type="Cube", translation=(0.0, 0.0, 0.62))
...@@ -185,8 +199,14 @@ class TestPhysicsSchema(unittest.TestCase): ...@@ -185,8 +199,14 @@ class TestPhysicsSchema(unittest.TestCase):
Helper functions. Helper functions.
""" """
def _validate_articulation_properties_on_prim(self, prim_path: str, verbose: bool = False): def _validate_articulation_properties_on_prim(
"""Validate the articulation properties on the prim.""" self, prim_path: str, has_default_fixed_root: False, verbose: bool = False
):
"""Validate the articulation properties on the prim.
If :attr:`has_default_fixed_root` is True, then the asset already has a fixed root link. This is used to check the
expected behavior of the fixed root link configuration.
"""
# the root prim # the root prim
root_prim = prim_utils.get_prim_at_path(prim_path) root_prim = prim_utils.get_prim_at_path(prim_path)
# check articulation properties are set correctly # check articulation properties are set correctly
...@@ -194,6 +214,24 @@ class TestPhysicsSchema(unittest.TestCase): ...@@ -194,6 +214,24 @@ class TestPhysicsSchema(unittest.TestCase):
# skip names we know are not present # skip names we know are not present
if attr_name == "func": if attr_name == "func":
continue continue
# handle fixed root link
if attr_name == "fix_root_link" and attr_value is not None:
# obtain the fixed joint prim
fixed_joint_prim = find_global_fixed_joint_prim(prim_path)
# if asset does not have a fixed root link then check if the joint is created
if not has_default_fixed_root:
if attr_value:
self.assertIsNotNone(fixed_joint_prim)
else:
self.assertIsNone(fixed_joint_prim)
else:
# check a joint exists
self.assertIsNotNone(fixed_joint_prim)
# check if the joint is enabled or disabled
is_enabled = fixed_joint_prim.GetJointEnabledAttr().Get()
self.assertEqual(is_enabled, attr_value)
# skip the rest of the checks
continue
# convert attribute name in prim to cfg name # convert attribute name in prim to cfg name
prim_prop_name = f"physxArticulation:{to_camel_case(attr_name, to='cC')}" prim_prop_name = f"physxArticulation:{to_camel_case(attr_name, to='cC')}"
# validate the values # validate the values
......
...@@ -20,6 +20,7 @@ import omni.isaac.core.utils.prims as prim_utils ...@@ -20,6 +20,7 @@ import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils import omni.isaac.core.utils.stage as stage_utils
import omni.isaac.orbit.sim as sim_utils import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR, ISAAC_ORBIT_NUCLEUS_DIR
class TestUtilities(unittest.TestCase): class TestUtilities(unittest.TestCase):
...@@ -82,6 +83,29 @@ class TestUtilities(unittest.TestCase): ...@@ -82,6 +83,29 @@ class TestUtilities(unittest.TestCase):
with self.assertRaises(ValueError): with self.assertRaises(ValueError):
sim_utils.get_all_matching_child_prims("World/Floor_.*") sim_utils.get_all_matching_child_prims("World/Floor_.*")
def test_find_global_fixed_joint_prim(self):
"""Test find_global_fixed_joint_prim() function."""
# create scene
prim_utils.create_prim("/World")
prim_utils.create_prim(
"/World/ANYmal", usd_path=f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd"
)
prim_utils.create_prim(
"/World/Franka", usd_path=f"{ISAAC_ORBIT_NUCLEUS_DIR}/Robots/FrankaEmika/panda_instanceable.usd"
)
prim_utils.create_prim("/World/Franka_Isaac", usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Franka/franka.usd")
# test
self.assertIsNone(sim_utils.find_global_fixed_joint_prim("/World/ANYmal"))
self.assertIsNotNone(sim_utils.find_global_fixed_joint_prim("/World/Franka"))
self.assertIsNotNone(sim_utils.find_global_fixed_joint_prim("/World/Franka_Isaac"))
# make fixed joint disabled manually
joint_prim = sim_utils.find_global_fixed_joint_prim("/World/Franka")
joint_prim.GetJointEnabledAttr().Set(False)
self.assertIsNotNone(sim_utils.find_global_fixed_joint_prim("/World/Franka"))
self.assertIsNone(sim_utils.find_global_fixed_joint_prim("/World/Franka", check_enabled_only=True))
if __name__ == "__main__": if __name__ == "__main__":
run_tests() run_tests()
...@@ -20,6 +20,7 @@ from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR ...@@ -20,6 +20,7 @@ from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
RIDGEBACK_FRANKA_PANDA_CFG = ArticulationCfg( RIDGEBACK_FRANKA_PANDA_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg( spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Clearpath/RidgebackFranka/ridgeback_franka.usd", usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Clearpath/RidgebackFranka/ridgeback_franka.usd",
articulation_props=sim_utils.ArticulationRootPropertiesCfg(enabled_self_collisions=False),
activate_contact_sensors=False, activate_contact_sensors=False,
), ),
init_state=ArticulationCfg.InitialStateCfg( init_state=ArticulationCfg.InitialStateCfg(
......
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