Unverified Commit af088f59 authored by James Smith's avatar James Smith Committed by GitHub

Expands on articulation test for multiple instances and devices (#872)

# Description

Expands upon `test_articulation.py` to test with mulitple robots and on
both CPU / GPU.

Fixes #861 

## 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
`./isaaclab.sh --format`
- [ ] 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
- [ ] 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 1aabdcbc
...@@ -10,8 +10,10 @@ ...@@ -10,8 +10,10 @@
from omni.isaac.lab.app import AppLauncher, run_tests from omni.isaac.lab.app import AppLauncher, run_tests
HEADLESS = True
# launch omniverse app # launch omniverse app
app_launcher = AppLauncher(headless=True) app_launcher = AppLauncher(headless=HEADLESS)
simulation_app = app_launcher.app simulation_app = app_launcher.app
"""Rest everything follows.""" """Rest everything follows."""
...@@ -19,13 +21,15 @@ simulation_app = app_launcher.app ...@@ -19,13 +21,15 @@ simulation_app = app_launcher.app
import ctypes import ctypes
import torch import torch
import unittest import unittest
from typing import Literal
import omni.isaac.core.utils.stage as stage_utils import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.lab.sim as sim_utils import omni.isaac.lab.sim as sim_utils
import omni.isaac.lab.utils.string as string_utils import omni.isaac.lab.utils.string as string_utils
from omni.isaac.lab.actuators import ImplicitActuatorCfg from omni.isaac.lab.actuators import ImplicitActuatorCfg
from omni.isaac.lab.assets import Articulation, ArticulationCfg from omni.isaac.lab.assets import Articulation, ArticulationCfg
from omni.isaac.lab.sim import build_simulation_context
from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR
## ##
...@@ -34,569 +38,760 @@ from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR ...@@ -34,569 +38,760 @@ from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR
from omni.isaac.lab_assets import ANYMAL_C_CFG, FRANKA_PANDA_CFG, SHADOW_HAND_CFG # isort:skip from omni.isaac.lab_assets import ANYMAL_C_CFG, FRANKA_PANDA_CFG, SHADOW_HAND_CFG # isort:skip
def generate_articulation_cfg(
articulation_type: Literal["humanoid", "panda", "anymal", "shadow_hand", "single_joint"],
stiffness: float | None = 10.0,
damping: float | None = 2.0,
) -> ArticulationCfg:
"""Generate an articulation configuration.
Args:
articulation_type: Type of articulation to generate.
stiffness: Stiffness value for the articulation's actuators. Only currently used for humanoid.
damping: Damping value for the articulation's actuators. Only currently used for humanoid.
Returns:
The articulation configuration for the requested articulation type.
"""
if articulation_type == "humanoid":
articulation_cfg = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Humanoid/humanoid_instanceable.usd"),
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 1.34)),
actuators={"body": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=stiffness, damping=damping)},
)
elif articulation_type == "panda":
articulation_cfg = FRANKA_PANDA_CFG
elif articulation_type == "anymal":
articulation_cfg = ANYMAL_C_CFG
elif articulation_type == "shadow_hand":
articulation_cfg = SHADOW_HAND_CFG
elif articulation_type == "single_joint":
articulation_cfg = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Simple/revolute_articulation.usd"),
actuators={
"joint": ImplicitActuatorCfg(
joint_names_expr=[".*"],
effort_limit=400.0,
velocity_limit=100.0,
stiffness=0.0,
damping=10.0,
),
},
)
else:
raise ValueError(
f"Invalid articulation type: {articulation_type}, valid options are 'humanoid', 'panda', 'anymal',"
" 'shadow_hand' and 'single_joint'."
)
return articulation_cfg
def generate_articulation(
articulation_cfg: ArticulationCfg, num_articulations: int, device: str
) -> tuple[Articulation, torch.tensor]:
"""Generate an articulation from a configuration.
Handles the creation of the articulation, the environment prims and the articulation's environment
translations
Args:
articulation_cfg: Articulation configuration.
num_articulations: Number of articulations to generate.
device: Device to use for the tensors.
Returns:
The articulation and environment translations.
"""
# Generate translations of 1.5m in x for each articulation
translations = torch.zeros(num_articulations, 3, device=device)
translations[:, 0] = torch.arange(num_articulations) * 1.5
# Create Top-level Xforms, one for each articulation
for i in range(num_articulations):
prim_utils.create_prim(f"/World/Env_{i}", "Xform", translation=translations[i][:3])
articulation = Articulation(articulation_cfg.replace(prim_path="/World/Env_.*/Robot"))
return articulation, translations
class TestArticulation(unittest.TestCase): class TestArticulation(unittest.TestCase):
"""Test for articulation class.""" """Test for articulation class."""
def setUp(self):
"""Create a blank new stage for each test."""
# Create a new stage
stage_utils.create_new_stage()
# Simulation time-step
self.dt = 0.005
# Load kit helper
sim_cfg = sim_utils.SimulationCfg(dt=self.dt, device="cuda:0")
self.sim = sim_utils.SimulationContext(sim_cfg)
def tearDown(self):
"""Stops simulator after each test."""
# stop simulation
self.sim.stop()
# clear the stage
self.sim.clear_all_callbacks()
self.sim.clear_instance()
""" """
Tests Tests
""" """
def test_initialization_floating_base_non_root(self): def test_initialization_floating_base_non_root(self):
"""Test initialization for a floating-base with articulation root on a rigid body """Test initialization for a floating-base with articulation root on a rigid body.
under the provided prim path.""" under the provided prim path."""
# Create articulation for num_articulations in (1, 2):
robot_cfg = ArticulationCfg( for device in ("cuda:0", "cpu"):
prim_path="/World/Robot", with self.subTest(num_articulations=num_articulations, device=device):
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Humanoid/humanoid_instanceable.usd"), with build_simulation_context(device=device, add_ground_plane=True, auto_add_lighting=True) as sim:
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 1.34)), articulation_cfg = generate_articulation_cfg(
actuators={"body": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=0.0, damping=0.0)}, articulation_type="humanoid", stiffness=0.0, damping=0.0
) )
robot = Articulation(cfg=robot_cfg) articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
# Check that boundedness of articulation is correct # Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Play sim # Play sim
self.sim.reset() sim.reset()
# Check that boundedness of articulation is correct # # Check if articulation is initialized
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) self.assertTrue(articulation.is_initialized)
# Check that is fixed base
# Check if robot is initialized self.assertFalse(articulation.is_fixed_base)
self.assertTrue(robot.is_initialized) # Check buffers that exists and have correct shapes
# Check that floating base self.assertEqual(articulation.data.root_pos_w.shape, (num_articulations, 3))
self.assertFalse(robot.is_fixed_base) self.assertEqual(articulation.data.root_quat_w.shape, (num_articulations, 4))
# Check buffers that exists and have correct shapes self.assertEqual(articulation.data.joint_pos.shape, (num_articulations, 21))
self.assertTrue(robot.data.root_pos_w.shape == (1, 3))
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) # Check some internal physx data for debugging
self.assertTrue(robot.data.joint_pos.shape == (1, 21)) # -- joint related
self.assertEqual(
# Check some internal physx data for debugging articulation.root_physx_view.max_dofs,
# -- joint related articulation.root_physx_view.shared_metatype.dof_count,
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count) )
# -- link related # -- link related
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count) self.assertEqual(
# -- link names (check within articulation ordering is correct) articulation.root_physx_view.max_links,
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]] articulation.root_physx_view.shared_metatype.link_count,
self.assertListEqual(prim_path_body_names, robot.body_names) )
# -- link names (check within articulation ordering is correct)
# Simulate physics prim_path_body_names = [
for _ in range(10): path.split("/")[-1] for path in articulation.root_physx_view.link_paths[0]
# perform rendering ]
self.sim.step() self.assertListEqual(prim_path_body_names, articulation.body_names)
# update robot
robot.update(self.dt) # Simulate physics
for _ in range(10):
# perform rendering
sim.step()
# update articulation
articulation.update(sim.cfg.dt)
def test_initialization_floating_base(self): def test_initialization_floating_base(self):
"""Test initialization for a floating-base with articulation root on provided prim path.""" """Test initialization for a floating-base with articulation root on provided prim path."""
# Create articulation for num_articulations in (1, 2):
robot = Articulation(cfg=ANYMAL_C_CFG.replace(prim_path="/World/Robot")) for device in ("cuda:0", "cpu"):
with self.subTest(num_articulations=num_articulations, device=device):
# Check that boundedness of articulation is correct with build_simulation_context(device=device, add_ground_plane=True, auto_add_lighting=True) as sim:
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) articulation_cfg = generate_articulation_cfg(
articulation_type="anymal", stiffness=0.0, damping=0.0
# Play sim )
self.sim.reset() articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
# Check that boundedness of articulation is correct # Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Check if robot is initialized # Play sim
self.assertTrue(robot.is_initialized) sim.reset()
# Check that floating base # Check if articulation is initialized
self.assertFalse(robot.is_fixed_base) self.assertTrue(articulation.is_initialized)
# Check buffers that exists and have correct shapes # Check that floating base
self.assertTrue(robot.data.root_pos_w.shape == (1, 3)) self.assertFalse(articulation.is_fixed_base)
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) # Check buffers that exists and have correct shapes
self.assertTrue(robot.data.joint_pos.shape == (1, 12)) self.assertEqual(articulation.data.root_pos_w.shape, (num_articulations, 3))
self.assertEqual(articulation.data.root_quat_w.shape, (num_articulations, 4))
# Check some internal physx data for debugging self.assertEqual(articulation.data.joint_pos.shape, (num_articulations, 12))
# -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count) # Check some internal physx data for debugging
# -- link related # -- joint related
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count) self.assertEqual(
# -- link names (check within articulation ordering is correct) articulation.root_physx_view.max_dofs,
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]] articulation.root_physx_view.shared_metatype.dof_count,
self.assertListEqual(prim_path_body_names, robot.body_names) )
# -- link related
# Simulate physics self.assertEqual(
for _ in range(10): articulation.root_physx_view.max_links,
# perform rendering articulation.root_physx_view.shared_metatype.link_count,
self.sim.step() )
# update robot # -- link names (check within articulation ordering is correct)
robot.update(self.dt) prim_path_body_names = [
path.split("/")[-1] for path in articulation.root_physx_view.link_paths[0]
]
self.assertListEqual(prim_path_body_names, articulation.body_names)
# Simulate physics
for _ in range(10):
# perform rendering
sim.step()
# update articulation
articulation.update(sim.cfg.dt)
def test_initialization_fixed_base(self): def test_initialization_fixed_base(self):
"""Test initialization for fixed base.""" """Test initialization for fixed base."""
# Create articulation for num_articulations in (1, 2):
robot = Articulation(cfg=FRANKA_PANDA_CFG.replace(prim_path="/World/Robot")) for device in ("cuda:0", "cpu"):
with self.subTest(num_articulations=num_articulations, device=device):
# Check that boundedness of articulation is correct with build_simulation_context(device=device, add_ground_plane=False, auto_add_lighting=True) as sim:
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) articulation_cfg = generate_articulation_cfg(articulation_type="panda")
articulation, translations = generate_articulation(articulation_cfg, num_articulations, device)
# Play sim
self.sim.reset() # Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) # Play sim
sim.reset()
# Check if robot is initialized # Check if articulation is initialized
self.assertTrue(robot.is_initialized) self.assertTrue(articulation.is_initialized)
# Check that fixed base # Check that fixed base
self.assertTrue(robot.is_fixed_base) self.assertTrue(articulation.is_fixed_base)
# Check buffers that exists and have correct shapes # Check buffers that exists and have correct shapes
self.assertTrue(robot.data.root_pos_w.shape == (1, 3)) self.assertEqual(articulation.data.root_pos_w.shape, (num_articulations, 3))
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertEqual(articulation.data.root_quat_w.shape, (num_articulations, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 9)) self.assertEqual(articulation.data.joint_pos.shape, (num_articulations, 9))
# Check some internal physx data for debugging # Check some internal physx data for debugging
# -- joint related # -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count) self.assertEqual(
# -- link related articulation.root_physx_view.max_dofs,
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count) articulation.root_physx_view.shared_metatype.dof_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]] # -- link related
self.assertListEqual(prim_path_body_names, robot.body_names) self.assertEqual(
articulation.root_physx_view.max_links,
# Simulate physics articulation.root_physx_view.shared_metatype.link_count,
for _ in range(10): )
# perform rendering # -- link names (check within articulation ordering is correct)
self.sim.step() prim_path_body_names = [
# update robot path.split("/")[-1] for path in articulation.root_physx_view.link_paths[0]
robot.update(self.dt) ]
# check that the root is at the correct state self.assertListEqual(prim_path_body_names, articulation.body_names)
default_root_state = robot.data.default_root_state.clone()
torch.testing.assert_close(robot.data.root_state_w, default_root_state) # Simulate physics
for _ in range(10):
# perform rendering
sim.step()
# update articulation
articulation.update(sim.cfg.dt)
# check that the root is at the correct state - its default state as it is fixed base
default_root_state = articulation.data.default_root_state.clone()
default_root_state[:, :3] = default_root_state[:, :3] + translations
torch.testing.assert_close(articulation.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."""
# Create articulation for num_articulations in (1, 2):
robot_cfg = ArticulationCfg( for device in ("cuda:0", "cpu"):
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Simple/revolute_articulation.usd"), with self.subTest(num_articulations=num_articulations, device=device):
actuators={ with build_simulation_context(device=device, add_ground_plane=True, auto_add_lighting=True) as sim:
"joint": ImplicitActuatorCfg( articulation_cfg = generate_articulation_cfg(articulation_type="single_joint")
joint_names_expr=[".*"], articulation, translations = generate_articulation(articulation_cfg, num_articulations, device)
effort_limit=400.0,
velocity_limit=100.0, # Check that boundedness of articulation is correct
stiffness=0.0, self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
damping=10.0,
), # Play sim
}, sim.reset()
) # Check if articulation is initialized
robot = Articulation(cfg=robot_cfg.replace(prim_path="/World/Robot")) self.assertTrue(articulation.is_initialized)
# Check that fixed base
# Check that boundedness of articulation is correct self.assertTrue(articulation.is_fixed_base)
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) # Check buffers that exists and have correct shapes
self.assertEqual(articulation.data.root_pos_w.shape, (num_articulations, 3))
# Play sim self.assertEqual(articulation.data.root_quat_w.shape, (num_articulations, 4))
self.sim.reset() self.assertEqual(articulation.data.joint_pos.shape, (num_articulations, 1))
# Check that boundedness of articulation is correct # Check some internal physx data for debugging
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) # -- joint related
self.assertEqual(
# Check if robot is initialized articulation.root_physx_view.max_dofs,
self.assertTrue(robot.is_initialized) articulation.root_physx_view.shared_metatype.dof_count,
# Check that fixed base )
self.assertTrue(robot.is_fixed_base) # -- link related
# Check buffers that exists and have correct shapes self.assertEqual(
self.assertTrue(robot.data.root_pos_w.shape == (1, 3)) articulation.root_physx_view.max_links,
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) articulation.root_physx_view.shared_metatype.link_count,
self.assertTrue(robot.data.joint_pos.shape == (1, 1)) )
# -- link names (check within articulation ordering is correct)
# Check some internal physx data for debugging prim_path_body_names = [
# -- joint related path.split("/")[-1] for path in articulation.root_physx_view.link_paths[0]
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count) ]
# -- link related self.assertListEqual(prim_path_body_names, articulation.body_names)
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count)
# -- link names (check within articulation ordering is correct) # Simulate physics
prim_path_body_names = [path.split("/")[-1] for path in robot.root_physx_view.link_paths[0]] for _ in range(10):
self.assertListEqual(prim_path_body_names, robot.body_names) # perform rendering
sim.step()
# Simulate physics # update articulation
for _ in range(10): articulation.update(sim.cfg.dt)
# perform rendering
self.sim.step() # check that the root is at the correct state - its default state as it is fixed base
# update robot default_root_state = articulation.data.default_root_state.clone()
robot.update(self.dt) default_root_state[:, :3] = default_root_state[:, :3] + translations
torch.testing.assert_close(articulation.data.root_state_w, default_root_state)
def test_initialization_hand_with_tendons(self): def test_initialization_hand_with_tendons(self):
"""Test initialization for fixed base articulated hand with tendons.""" """Test initialization for fixed base articulated hand with tendons."""
# Create articulation for num_articulations in (1, 2):
robot_cfg = SHADOW_HAND_CFG for device in ("cuda:0", "cpu"):
robot = Articulation(cfg=robot_cfg.replace(prim_path="/World/Robot")) with self.subTest(num_articulations=num_articulations, device=device):
with build_simulation_context(device=device, add_ground_plane=False, auto_add_lighting=True) as sim:
# Check that boundedness of articulation is correct articulation_cfg = generate_articulation_cfg(articulation_type="shadow_hand")
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
# Play sim # Check that boundedness of articulation is correct
self.sim.reset() self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Check that boundedness of articulation is correct # Play sim
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) sim.reset()
# Check if articulation is initialized
# Check if robot is initialized self.assertTrue(articulation.is_initialized)
self.assertTrue(robot.is_initialized) # Check that fixed base
# Check that fixed base self.assertTrue(articulation.is_fixed_base)
self.assertTrue(robot.is_fixed_base) # Check buffers that exists and have correct shapes
# Check buffers that exists and have correct shapes self.assertTrue(articulation.data.root_pos_w.shape == (num_articulations, 3))
self.assertTrue(robot.data.root_pos_w.shape == (1, 3)) self.assertTrue(articulation.data.root_quat_w.shape == (num_articulations, 4))
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertTrue(articulation.data.joint_pos.shape == (num_articulations, 24))
self.assertTrue(robot.data.joint_pos.shape == (1, 24))
# Check some internal physx data for debugging
# Check some internal physx data for debugging # -- joint related
# -- joint related self.assertEqual(
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count) articulation.root_physx_view.max_dofs,
# -- link related articulation.root_physx_view.shared_metatype.dof_count,
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count) )
# -- link related
# Simulate physics self.assertEqual(
for _ in range(10): articulation.root_physx_view.max_links,
# perform rendering articulation.root_physx_view.shared_metatype.link_count,
self.sim.step() )
# update robot
robot.update(self.dt) # Simulate physics
for _ in range(10):
# perform rendering
sim.step()
# update articulation
articulation.update(sim.cfg.dt)
def test_initialization_floating_base_made_fixed_base(self): def test_initialization_floating_base_made_fixed_base(self):
"""Test initialization for a floating-base articulation made fixed-base using schema properties.""" """Test initialization for a floating-base articulation made fixed-base using schema properties."""
# Create articulation for num_articulations in (1, 2):
robot_cfg: ArticulationCfg = ANYMAL_C_CFG.replace(prim_path="/World/Robot") for device in ("cuda:0", "cpu"):
robot_cfg.spawn.articulation_props.fix_root_link = True with self.subTest(num_articulations=num_articulations, device=device):
robot = Articulation(cfg=robot_cfg) with build_simulation_context(device=device, add_ground_plane=True, auto_add_lighting=True) as sim:
articulation_cfg = generate_articulation_cfg(articulation_type="anymal")
# Check that boundedness of articulation is correct # Fix root link
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) articulation_cfg.spawn.articulation_props.fix_root_link = True
articulation, translations = generate_articulation(articulation_cfg, num_articulations, device)
# Play sim
self.sim.reset() # Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) # Play sim
sim.reset()
# Check if robot is initialized # Check if articulation is initialized
self.assertTrue(robot.is_initialized) self.assertTrue(articulation.is_initialized)
# Check that floating base # Check that is fixed base
self.assertTrue(robot.is_fixed_base) self.assertTrue(articulation.is_fixed_base)
# Check buffers that exists and have correct shapes # Check buffers that exists and have correct shapes
self.assertTrue(robot.data.root_pos_w.shape == (1, 3)) self.assertEqual(articulation.data.root_pos_w.shape, (num_articulations, 3))
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertEqual(articulation.data.root_quat_w.shape, (num_articulations, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 12)) self.assertEqual(articulation.data.joint_pos.shape, (num_articulations, 12))
# Check some internal physx data for debugging # Check some internal physx data for debugging
# -- joint related # -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count) self.assertEqual(
# -- link related articulation.root_physx_view.max_dofs,
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count) articulation.root_physx_view.shared_metatype.dof_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]] # -- link related
self.assertListEqual(prim_path_body_names, robot.body_names) self.assertEqual(
articulation.root_physx_view.max_links,
# Root state should be at the default state articulation.root_physx_view.shared_metatype.link_count,
robot.write_root_state_to_sim(robot.data.default_root_state.clone()) )
# Simulate physics # -- link names (check within articulation ordering is correct)
for _ in range(10): prim_path_body_names = [
# perform rendering path.split("/")[-1] for path in articulation.root_physx_view.link_paths[0]
self.sim.step() ]
# update robot self.assertListEqual(prim_path_body_names, articulation.body_names)
robot.update(self.dt)
# check that the root is at the correct state # Simulate physics
default_root_state = robot.data.default_root_state.clone() for _ in range(10):
torch.testing.assert_close(robot.data.root_state_w, default_root_state) # perform rendering
sim.step()
# update articulation
articulation.update(sim.cfg.dt)
# check that the root is at the correct state - its default state as it is fixed base
default_root_state = articulation.data.default_root_state.clone()
default_root_state[:, :3] = default_root_state[:, :3] + translations
torch.testing.assert_close(articulation.data.root_state_w, default_root_state)
def test_initialization_fixed_base_made_floating_base(self): def test_initialization_fixed_base_made_floating_base(self):
"""Test initialization for fixed base made floating-base using schema properties.""" """Test initialization for fixed base made floating-base using schema properties."""
# Create articulation for num_articulations in (1, 2):
robot_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/Robot") for device in ("cuda:0", "cpu"):
robot_cfg.spawn.articulation_props.fix_root_link = False with self.subTest(num_articulations=num_articulations, device=device):
robot = Articulation(cfg=robot_cfg) with build_simulation_context(device=device, add_ground_plane=True, auto_add_lighting=True) as sim:
articulation_cfg = generate_articulation_cfg(articulation_type="panda")
# Check that boundedness of articulation is correct # Unfix root link
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) articulation_cfg.spawn.articulation_props.fix_root_link = False
articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
# Play sim
self.sim.reset() # Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) # Play sim
sim.reset()
# Check if robot is initialized # Check if articulation is initialized
self.assertTrue(robot.is_initialized) self.assertTrue(articulation.is_initialized)
# Check that fixed base # Check that is floating base
self.assertFalse(robot.is_fixed_base) self.assertFalse(articulation.is_fixed_base)
# Check buffers that exists and have correct shapes # Check buffers that exists and have correct shapes
self.assertTrue(robot.data.root_pos_w.shape == (1, 3)) self.assertEqual(articulation.data.root_pos_w.shape, (num_articulations, 3))
self.assertTrue(robot.data.root_quat_w.shape == (1, 4)) self.assertEqual(articulation.data.root_quat_w.shape, (num_articulations, 4))
self.assertTrue(robot.data.joint_pos.shape == (1, 9)) self.assertEqual(articulation.data.joint_pos.shape, (num_articulations, 9))
# Check some internal physx data for debugging # Check some internal physx data for debugging
# -- joint related # -- joint related
self.assertEqual(robot.root_physx_view.max_dofs, robot.root_physx_view.shared_metatype.dof_count) self.assertEqual(
# -- link related articulation.root_physx_view.max_dofs,
self.assertEqual(robot.root_physx_view.max_links, robot.root_physx_view.shared_metatype.link_count) articulation.root_physx_view.shared_metatype.dof_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]] # -- link related
self.assertListEqual(prim_path_body_names, robot.body_names) self.assertEqual(
articulation.root_physx_view.max_links,
# Simulate physics articulation.root_physx_view.shared_metatype.link_count,
for _ in range(10): )
# perform rendering # -- link names (check within articulation ordering is correct)
self.sim.step() prim_path_body_names = [
# update robot path.split("/")[-1] for path in articulation.root_physx_view.link_paths[0]
robot.update(self.dt) ]
# check that the root is at the correct state self.assertListEqual(prim_path_body_names, articulation.body_names)
default_root_state = robot.data.default_root_state.clone()
is_close = torch.any(torch.isclose(robot.data.root_state_w, default_root_state)) # Simulate physics
self.assertFalse(is_close) for _ in range(10):
# perform rendering
sim.step()
# update articulation
articulation.update(sim.cfg.dt)
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 for num_articulations in (1, 2):
robot_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/Robot") for device in ("cuda:0", "cpu"):
robot_cfg.init_state.joint_pos = { with self.subTest(num_articulations=num_articulations, device=device):
"panda_joint1": 10.0, with build_simulation_context(device=device, add_ground_plane=True, auto_add_lighting=True) as sim:
"panda_joint[2, 4]": -20.0, # Create articulation
} articulation_cfg = generate_articulation_cfg(articulation_type="panda")
robot = Articulation(robot_cfg) articulation_cfg.init_state.joint_pos = {
"panda_joint1": 10.0,
# Check that boundedness of articulation is correct "panda_joint[2, 4]": -20.0,
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) }
# Play sim articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
self.sim.reset()
# Check if robot is initialized # Check that boundedness of articulation is correct
self.assertFalse(robot.is_initialized) self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Play sim
sim.reset()
# Check if articulation is initialized
self.assertFalse(articulation._is_initialized)
def test_out_of_range_default_joint_vel(self): def test_out_of_range_default_joint_vel(self):
"""Test that the default joint velocity from configuration is out of range.""" """Test that the default joint velocity from configuration is out of range."""
# Create articulation with build_simulation_context(device="cuda:0", add_ground_plane=False, auto_add_lighting=True) as sim:
robot_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/Robot") # Create articulation
robot_cfg.init_state.joint_vel = { articulation_cfg = FRANKA_PANDA_CFG.replace(prim_path="/World/Robot")
"panda_joint1": 100.0, articulation_cfg.init_state.joint_vel = {
"panda_joint[2, 4]": -60.0, "panda_joint1": 100.0,
} "panda_joint[2, 4]": -60.0,
robot = Articulation(robot_cfg) }
articulation = Articulation(articulation_cfg)
# Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(robot)).value, 1) # Check that boundedness of articulation is correct
self.assertEqual(ctypes.c_long.from_address(id(articulation)).value, 1)
# Play sim
self.sim.reset() # Play sim
# Check if robot is initialized sim.reset()
self.assertFalse(robot.is_initialized) # Check if articulation is initialized
self.assertFalse(articulation._is_initialized)
def test_external_force_on_single_body(self): def test_external_force_on_single_body(self):
"""Test application of external force on the base of the robot.""" """Test application of external force on the base of the articulation."""
for num_articulations in (1, 2):
# Robots for device in ("cuda:0", "cpu"):
robot_cfg = ANYMAL_C_CFG with self.subTest(num_articulations=num_articulations, device=device):
robot_cfg.spawn.func("/World/Anymal_c/Robot_1", robot_cfg.spawn, translation=(0.0, -0.5, 0.65)) with build_simulation_context(device=device, add_ground_plane=False, auto_add_lighting=True) as sim:
robot_cfg.spawn.func("/World/Anymal_c/Robot_2", robot_cfg.spawn, translation=(0.0, 0.5, 0.65)) articulation_cfg = generate_articulation_cfg(articulation_type="anymal")
# create handles for the robots articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
robot = Articulation(robot_cfg.replace(prim_path="/World/Anymal_c/Robot.*")) # Play the simulator
sim.reset()
# Play the simulator
self.sim.reset() # Find bodies to apply the force
body_ids, _ = articulation.find_bodies("base")
# Find bodies to apply the force # Sample a large force
body_ids, _ = robot.find_bodies("base") external_wrench_b = torch.zeros(articulation.num_instances, len(body_ids), 6, device=sim.device)
# Sample a large force external_wrench_b[..., 1] = 1000.0
external_wrench_b = torch.zeros(robot.num_instances, len(body_ids), 6, device=self.sim.device)
external_wrench_b[..., 1] = 1000.0 # Now we are ready!
for _ in range(5):
# Now we are ready! # reset root state
for _ in range(5): root_state = articulation.data.default_root_state.clone()
# reset root state
root_state = robot.data.default_root_state.clone() articulation.write_root_state_to_sim(root_state)
root_state[0, :2] = torch.tensor([0.0, -0.5], device=self.sim.device) # reset dof state
root_state[1, :2] = torch.tensor([0.0, 0.5], device=self.sim.device) joint_pos, joint_vel = (
robot.write_root_state_to_sim(root_state) articulation.data.default_joint_pos,
# reset dof state articulation.data.default_joint_vel,
joint_pos, joint_vel = robot.data.default_joint_pos, robot.data.default_joint_vel )
robot.write_joint_state_to_sim(joint_pos, joint_vel) articulation.write_joint_state_to_sim(joint_pos, joint_vel)
# reset robot # reset articulation
robot.reset() articulation.reset()
# apply force # apply force
robot.set_external_force_and_torque( articulation.set_external_force_and_torque(
external_wrench_b[..., :3], external_wrench_b[..., 3:], body_ids=body_ids external_wrench_b[..., :3], external_wrench_b[..., 3:], body_ids=body_ids
) )
# perform simulation # perform simulation
for _ in range(100): for _ in range(100):
# apply action to the robot # apply action to the articulation
robot.set_joint_position_target(robot.data.default_joint_pos.clone()) articulation.set_joint_position_target(articulation.data.default_joint_pos.clone())
robot.write_data_to_sim() articulation.write_data_to_sim()
# perform step # perform step
self.sim.step() sim.step()
# update buffers # update buffers
robot.update(self.dt) articulation.update(sim.cfg.dt)
# check condition that the robots have fallen down # check condition that the articulations have fallen down
self.assertTrue(robot.data.root_pos_w[0, 2].item() < 0.2) for i in range(num_articulations):
self.assertTrue(robot.data.root_pos_w[1, 2].item() < 0.2) self.assertLess(articulation.data.root_pos_w[i, 2].item(), 0.2)
def test_external_force_on_multiple_bodies(self): def test_external_force_on_multiple_bodies(self):
"""Test application of external force on the legs of the robot.""" """Test application of external force on the legs of the articulation."""
for num_articulations in (1, 2):
# Robots for device in ("cuda:0", "cpu"):
robot_cfg = ANYMAL_C_CFG with self.subTest(num_articulations=num_articulations, device=device):
robot_cfg.spawn.func("/World/Anymal_c/Robot_1", robot_cfg.spawn, translation=(0.0, -0.5, 0.65)) with build_simulation_context(device=device, add_ground_plane=False, auto_add_lighting=True) as sim:
robot_cfg.spawn.func("/World/Anymal_c/Robot_2", robot_cfg.spawn, translation=(0.0, 0.5, 0.65)) articulation_cfg = generate_articulation_cfg(articulation_type="anymal")
# create handles for the robots articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
robot = Articulation(robot_cfg.replace(prim_path="/World/Anymal_c/Robot.*"))
# Play the simulator
# Play the simulator sim.reset()
self.sim.reset()
# Find bodies to apply the force
# Find bodies to apply the force body_ids, _ = articulation.find_bodies(".*_SHANK")
body_ids, _ = robot.find_bodies(".*_SHANK") # Sample a large force
# Sample a large force external_wrench_b = torch.zeros(articulation.num_instances, len(body_ids), 6, device=sim.device)
external_wrench_b = torch.zeros(robot.num_instances, len(body_ids), 6, device=self.sim.device) external_wrench_b[..., 1] = 100.0
external_wrench_b[..., 1] = 100.0
# Now we are ready!
# Now we are ready! for _ in range(5):
for _ in range(5): # reset root state
# reset root state articulation.write_root_state_to_sim(articulation.data.default_root_state.clone())
root_state = robot.data.default_root_state.clone() # reset dof state
root_state[0, :2] = torch.tensor([0.0, -0.5], device=self.sim.device) joint_pos, joint_vel = (
root_state[1, :2] = torch.tensor([0.0, 0.5], device=self.sim.device) articulation.data.default_joint_pos,
robot.write_root_state_to_sim(root_state) articulation.data.default_joint_vel,
# reset dof state )
joint_pos, joint_vel = robot.data.default_joint_pos, robot.data.default_joint_vel articulation.write_joint_state_to_sim(joint_pos, joint_vel)
robot.write_joint_state_to_sim(joint_pos, joint_vel) # reset articulation
# reset robot articulation.reset()
robot.reset() # apply force
# apply force articulation.set_external_force_and_torque(
robot.set_external_force_and_torque( external_wrench_b[..., :3], external_wrench_b[..., 3:], body_ids=body_ids
external_wrench_b[..., :3], external_wrench_b[..., 3:], body_ids=body_ids )
) # perform simulation
# perform simulation for _ in range(100):
for _ in range(100): # apply action to the articulation
# apply action to the robot articulation.set_joint_position_target(articulation.data.default_joint_pos.clone())
robot.set_joint_position_target(robot.data.default_joint_pos.clone()) articulation.write_data_to_sim()
robot.write_data_to_sim() # perform step
# perform step sim.step()
self.sim.step() # update buffers
# update buffers articulation.update(sim.cfg.dt)
robot.update(self.dt) # check condition
# check condition for i in range(num_articulations):
# since there is a moment applied on the robot, the robot should rotate # since there is a moment applied on the articulation, the articulation should rotate
self.assertTrue(robot.data.root_ang_vel_w[0, 2].item() > 0.1) self.assertTrue(articulation.data.root_ang_vel_w[i, 2].item() > 0.1)
self.assertTrue(robot.data.root_ang_vel_w[1, 2].item() > 0.1)
def test_loading_gains_from_usd(self): def test_loading_gains_from_usd(self):
"""Test that gains are loaded from USD file if actuator model has them as None.""" """Test that gains are loaded from USD file if actuator model has them as None."""
# Create articulation for num_articulations in (1, 2):
robot_cfg = ArticulationCfg( for device in ("cuda:0", "cpu"):
prim_path="/World/Robot", with self.subTest(num_articulations=num_articulations, device=device):
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Humanoid/humanoid_instanceable.usd"), with build_simulation_context(device=device, add_ground_plane=False, auto_add_lighting=True) as sim:
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 1.34)), articulation_cfg = generate_articulation_cfg(
actuators={"body": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=None, damping=None)}, articulation_type="humanoid", stiffness=None, damping=None
) )
robot = Articulation(cfg=robot_cfg) articulation, _ = generate_articulation(articulation_cfg, num_articulations, device)
# Play sim # Play sim
self.sim.reset() sim.reset()
# Expected gains # Expected gains
# -- Stiffness values # -- Stiffness values
expected_stiffness = { expected_stiffness = {
".*_waist.*": 20.0, ".*_waist.*": 20.0,
".*_upper_arm.*": 10.0, ".*_upper_arm.*": 10.0,
"pelvis": 10.0, "pelvis": 10.0,
".*_lower_arm": 2.0, ".*_lower_arm": 2.0,
".*_thigh:0": 10.0, ".*_thigh:0": 10.0,
".*_thigh:1": 20.0, ".*_thigh:1": 20.0,
".*_thigh:2": 10.0, ".*_thigh:2": 10.0,
".*_shin": 5.0, ".*_shin": 5.0,
".*_foot.*": 2.0, ".*_foot.*": 2.0,
} }
indices_list, _, values_list = string_utils.resolve_matching_names_values(expected_stiffness, robot.joint_names) indices_list, _, values_list = string_utils.resolve_matching_names_values(
expected_stiffness = torch.zeros(robot.num_instances, robot.num_joints, device=robot.device) expected_stiffness, articulation.joint_names
expected_stiffness[:, indices_list] = torch.tensor(values_list, device=robot.device) )
# -- Damping values expected_stiffness = torch.zeros(
expected_damping = { articulation.num_instances, articulation.num_joints, device=articulation.device
".*_waist.*": 5.0, )
".*_upper_arm.*": 5.0, expected_stiffness[:, indices_list] = torch.tensor(values_list, device=articulation.device)
"pelvis": 5.0, # -- Damping values
".*_lower_arm": 1.0, expected_damping = {
".*_thigh:0": 5.0, ".*_waist.*": 5.0,
".*_thigh:1": 5.0, ".*_upper_arm.*": 5.0,
".*_thigh:2": 5.0, "pelvis": 5.0,
".*_shin": 0.1, ".*_lower_arm": 1.0,
".*_foot.*": 1.0, ".*_thigh:0": 5.0,
} ".*_thigh:1": 5.0,
indices_list, _, values_list = string_utils.resolve_matching_names_values(expected_damping, robot.joint_names) ".*_thigh:2": 5.0,
expected_damping = torch.zeros_like(expected_stiffness) ".*_shin": 0.1,
expected_damping[:, indices_list] = torch.tensor(values_list, device=robot.device) ".*_foot.*": 1.0,
}
# Check that gains are loaded from USD file indices_list, _, values_list = string_utils.resolve_matching_names_values(
torch.testing.assert_close(robot.actuators["body"].stiffness, expected_stiffness) expected_damping, articulation.joint_names
torch.testing.assert_close(robot.actuators["body"].damping, expected_damping) )
expected_damping = torch.zeros_like(expected_stiffness)
expected_damping[:, indices_list] = torch.tensor(values_list, device=articulation.device)
# Check that gains are loaded from USD file
torch.testing.assert_close(articulation.actuators["body"].stiffness, expected_stiffness)
torch.testing.assert_close(articulation.actuators["body"].damping, expected_damping)
def test_setting_gains_from_cfg(self): def test_setting_gains_from_cfg(self):
"""Test that gains are loaded from the configuration correctly. """Test that gains are loaded from the configuration correctly.
Note: We purposefully give one argument as int and other as float to check that it is handled correctly. Note: We purposefully give one argument as int and other as float to check that it is handled correctly.
""" """
# Create articulation for num_articulations in (1, 2):
robot_cfg = ArticulationCfg( for device in ("cuda:0", "cpu"):
prim_path="/World/Robot", with self.subTest(num_articulations=num_articulations, device=device):
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Humanoid/humanoid_instanceable.usd"), with build_simulation_context(device=device, add_ground_plane=True, auto_add_lighting=True) as sim:
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 1.34)), articulation_cfg = generate_articulation_cfg(articulation_type="humanoid")
actuators={"body": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness=10, damping=2.0)}, articulation, _ = generate_articulation(
) articulation_cfg=articulation_cfg, num_articulations=num_articulations, device=device
robot = Articulation(cfg=robot_cfg) )
# Play sim # Play sim
self.sim.reset() sim.reset()
# Expected gains # Expected gains
expected_stiffness = torch.full((robot.num_instances, robot.num_joints), 10.0, device=robot.device) expected_stiffness = torch.full(
expected_damping = torch.full_like(expected_stiffness, 2.0) (articulation.num_instances, articulation.num_joints), 10.0, device=articulation.device
)
# Check that gains are loaded from USD file expected_damping = torch.full_like(expected_stiffness, 2.0)
torch.testing.assert_close(robot.actuators["body"].stiffness, expected_stiffness)
torch.testing.assert_close(robot.actuators["body"].damping, expected_damping) # Check that gains are loaded from USD file
torch.testing.assert_close(articulation.actuators["body"].stiffness, expected_stiffness)
torch.testing.assert_close(articulation.actuators["body"].damping, expected_damping)
def test_setting_gains_from_cfg_dict(self): def test_setting_gains_from_cfg_dict(self):
"""Test that gains are loaded from the configuration dictionary correctly. """Test that gains are loaded from the configuration dictionary correctly.
Note: We purposefully give one argument as int and other as float to check that it is handled correctly. Note: We purposefully give one argument as int and other as float to check that it is handled correctly.
""" """
# Create articulation for num_articulations in (1, 2):
robot_cfg = ArticulationCfg( for device in ("cuda:0", "cpu"):
prim_path="/World/Robot", with self.subTest(num_articulations=num_articulations, device=device):
spawn=sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Humanoid/humanoid_instanceable.usd"), with build_simulation_context(device=device, add_ground_plane=False, auto_add_lighting=True) as sim:
init_state=ArticulationCfg.InitialStateCfg(pos=(0.0, 0.0, 1.34)), articulation_cfg = generate_articulation_cfg(articulation_type="humanoid")
actuators={"body": ImplicitActuatorCfg(joint_names_expr=[".*"], stiffness={".*": 10}, damping={".*": 2.0})}, articulation, _ = generate_articulation(
) articulation_cfg=articulation_cfg, num_articulations=num_articulations, device=device
robot = Articulation(cfg=robot_cfg) )
# Play sim
sim.reset()
# Expected gains
expected_stiffness = torch.full(
(articulation.num_instances, articulation.num_joints), 10.0, device=articulation.device
)
expected_damping = torch.full_like(expected_stiffness, 2.0)
# Check that gains are loaded from USD file
torch.testing.assert_close(articulation.actuators["body"].stiffness, expected_stiffness)
torch.testing.assert_close(articulation.actuators["body"].damping, expected_damping)
def test_reset(self):
"""Test that reset method works properly.
Need to check that all actuators are reset and that forces, torques and last body velocities are reset to 0.0.
NOTE: Currently no way to determine actuators have been reset, can leave this to actuator tests that
implement reset method.
# Play sim """
self.sim.reset() for num_articulations in (1, 2):
for device in ("cuda:0", "cpu"):
# Expected gains with self.subTest(num_articulations=num_articulations, device=device):
expected_stiffness = torch.full((robot.num_instances, robot.num_joints), 10.0, device=robot.device) with build_simulation_context(device=device, add_ground_plane=False, auto_add_lighting=True) as sim:
expected_damping = torch.full_like(expected_stiffness, 2.0) articulation_cfg = generate_articulation_cfg(articulation_type="humanoid")
articulation, _ = generate_articulation(
# Check that gains are loaded from USD file articulation_cfg=articulation_cfg, num_articulations=num_articulations, device=device
torch.testing.assert_close(robot.actuators["body"].stiffness, expected_stiffness) )
torch.testing.assert_close(robot.actuators["body"].damping, expected_damping)
# Play the simulator
sim.reset()
# Now we are ready!
# reset articulation
articulation.reset()
# Reset should zero external forces and torques
self.assertFalse(articulation.has_external_wrench)
self.assertEqual(torch.count_nonzero(articulation._external_force_b), 0)
self.assertEqual(torch.count_nonzero(articulation._external_torque_b), 0)
def test_apply_joint_command(self):
for num_articulations in (1, 2):
for device in ("cuda:0", "cpu"):
with self.subTest(num_articulations=num_articulations, device=device):
with build_simulation_context(
gravity_enabled=True, device=device, add_ground_plane=True, auto_add_lighting=True
) as sim:
articulation_cfg = generate_articulation_cfg(articulation_type="panda")
articulation, _ = generate_articulation(
articulation_cfg=articulation_cfg, num_articulations=num_articulations, device=device
)
# Play the simulator
sim.reset()
for _ in range(100):
# perform step
sim.step()
# update buffers
articulation.update(sim.cfg.dt)
# reset dof state
joint_pos = articulation.data.default_joint_pos
joint_pos[:, 3] = 0.0
# apply action to the articulation
articulation.set_joint_position_target(joint_pos)
articulation.write_data_to_sim()
for _ in range(100):
# perform step
sim.step()
# update buffers
articulation.update(sim.cfg.dt)
# Check that current joint position is not the same as default joint position, meaning
# the articulation moved. We can't check that it reached it's desired joint position as the gains
# are not properly tuned
assert not torch.allclose(articulation.data.joint_pos, joint_pos)
if __name__ == "__main__": if __name__ == "__main__":
......
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