Unverified Commit 361578f2 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Disables replicate physics for deformable teddy lift environment (#1026)

# Description

This MR fixes the teddy state machine example. Replicate physics doesn't
work for deformable bodies yet. Hence, calling more than one environment
was failing before. The flag is set to False now inside the post init of
the environment.

Fixes #1022

## Type of change

- Bug fix (non-breaking change which fixes an issue)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] 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 90b11509
......@@ -24,7 +24,7 @@ import omni.physics.tensors.impl.api as physx
import omni.isaac.lab.sim as sim_utils
import omni.isaac.lab.utils.math as math_utils
from omni.isaac.lab.actuators import ImplicitActuator
from omni.isaac.lab.assets import Articulation, RigidObject
from omni.isaac.lab.assets import Articulation, DeformableObject, RigidObject
from omni.isaac.lab.managers import SceneEntityCfg
from omni.isaac.lab.terrains import TerrainImporter
......@@ -824,6 +824,48 @@ def reset_joints_by_offset(
asset.write_joint_state_to_sim(joint_pos, joint_vel, env_ids=env_ids)
def reset_nodal_state_uniform(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
position_range: dict[str, tuple[float, float]],
velocity_range: dict[str, tuple[float, float]],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Reset the asset nodal state to a random position and velocity uniformly within the given ranges.
This function randomizes the nodal position and velocity of the asset.
* It samples the root position from the given ranges and adds them to the default nodal position, before setting
them into the physics simulation.
* It samples the root velocity from the given ranges and sets them into the physics simulation.
The function takes a dictionary of position and velocity ranges for each axis. The keys of the
dictionary are ``x``, ``y``, ``z``. The values are tuples of the form ``(min, max)``.
If the dictionary does not contain a key, the position or velocity is set to zero for that axis.
"""
# extract the used quantities (to enable type-hinting)
asset: DeformableObject = env.scene[asset_cfg.name]
# get default root state
nodal_state = asset.data.default_nodal_state_w[env_ids].clone()
# position
range_list = [position_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 1, 3), device=asset.device)
nodal_state[..., :3] += rand_samples
# velocities
range_list = [velocity_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 1, 3), device=asset.device)
nodal_state[..., 3:] += rand_samples
# set into the physics simulation
asset.write_nodal_state_to_sim(nodal_state, env_ids=env_ids)
def reset_scene_to_default(env: ManagerBasedEnv, env_ids: torch.Tensor):
"""Reset the scene to the default state specified in the scene configuration."""
# rigid bodies
......@@ -845,6 +887,11 @@ def reset_scene_to_default(env: ManagerBasedEnv, env_ids: torch.Tensor):
default_joint_vel = articulation_asset.data.default_joint_vel[env_ids].clone()
# set into the physics simulation
articulation_asset.write_joint_state_to_sim(default_joint_pos, default_joint_vel, env_ids=env_ids)
# deformable objects
for deformable_object in env.scene.deformable_objects.values():
# obtain default and set into the physics simulation
nodal_state = deformable_object.data.default_nodal_state_w[env_ids].clone()
deformable_object.write_nodal_state_to_sim(nodal_state, env_ids=env_ids)
"""
......
......@@ -6,10 +6,14 @@
from omni.isaac.lab.assets import DeformableObjectCfg
from omni.isaac.lab.controllers.differential_ik_cfg import DifferentialIKControllerCfg
from omni.isaac.lab.envs.mdp.actions.actions_cfg import DifferentialInverseKinematicsActionCfg
from omni.isaac.lab.managers import EventTermCfg as EventTerm
from omni.isaac.lab.managers import SceneEntityCfg
from omni.isaac.lab.sim.spawners import UsdFileCfg
from omni.isaac.lab.utils import configclass
from omni.isaac.lab.utils.assets import ISAACLAB_NUCLEUS_DIR
import omni.isaac.lab_tasks.manager_based.manipulation.lift.mdp as mdp
from . import joint_pos_env_cfg
##
......@@ -18,6 +22,11 @@ from . import joint_pos_env_cfg
from omni.isaac.lab_assets.franka import FRANKA_PANDA_HIGH_PD_CFG # isort: skip
##
# Rigid object lift environment.
##
@configclass
class FrankaCubeLiftEnvCfg(joint_pos_env_cfg.FrankaCubeLiftEnvCfg):
def __post_init__(self):
......@@ -50,6 +59,11 @@ class FrankaCubeLiftEnvCfg_PLAY(FrankaCubeLiftEnvCfg):
self.observations.policy.enable_corruption = False
##
# Deformable object lift environment.
##
@configclass
class FrankaTeddyBearLiftEnvCfg(FrankaCubeLiftEnvCfg):
def __post_init__(self):
......@@ -58,7 +72,7 @@ class FrankaTeddyBearLiftEnvCfg(FrankaCubeLiftEnvCfg):
self.scene.object = DeformableObjectCfg(
prim_path="{ENV_REGEX_NS}/Object",
init_state=DeformableObjectCfg.InitialStateCfg(pos=[0.5, 0, 0.05], rot=[0.707, 0, 0, 0.707]),
init_state=DeformableObjectCfg.InitialStateCfg(pos=(0.5, 0, 0.05), rot=(0.707, 0, 0, 0.707)),
spawn=UsdFileCfg(
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Objects/Teddy_Bear/teddy_bear.usd",
scale=(0.01, 0.01, 0.01),
......@@ -70,11 +84,27 @@ class FrankaTeddyBearLiftEnvCfg(FrankaCubeLiftEnvCfg):
self.scene.robot.actuators["panda_hand"].stiffness = 40.0
self.scene.robot.actuators["panda_hand"].damping = 10.0
# Remove all the terms for the lift_teddy_bear_sm demo
# Disable replicate physics as it doesn't work for deformable objects
# FIXME: This should be fixed by the PhysX replication system.
self.scene.replicate_physics = False
# Set events for the specific object type (deformable cube)
self.events.reset_object_position = EventTerm(
func=mdp.reset_nodal_state_uniform,
mode="reset",
params={
"position_range": {"x": (-0.1, 0.1), "y": (-0.25, 0.25), "z": (0.0, 0.0)},
"velocity_range": {},
"asset_cfg": SceneEntityCfg("object"),
},
)
# Remove all the terms for the state machine demo
# TODO: Computing the root pose of deformable object from nodal positions is expensive.
# We need to fix that part before enabling these terms for the training.
self.terminations.object_dropping = None
self.rewards.reaching_object = None
self.rewards.lifting_object = None
self.rewards.object_goal_tracking = None
self.rewards.object_goal_tracking_fine_grained = None
self.events.reset_object_position = None
self.observations.policy.object_position = None
......@@ -6,7 +6,7 @@
from dataclasses import MISSING
import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg
from omni.isaac.lab.assets import ArticulationCfg, AssetBaseCfg, DeformableObjectCfg, RigidObjectCfg
from omni.isaac.lab.envs import ManagerBasedRLEnvCfg
from omni.isaac.lab.managers import CurriculumTermCfg as CurrTerm
from omni.isaac.lab.managers import EventTermCfg as EventTerm
......@@ -40,7 +40,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg):
# end-effector sensor: will be populated by agent env cfg
ee_frame: FrameTransformerCfg = MISSING
# target object: will be populated by agent env cfg
object: RigidObjectCfg = MISSING
object: RigidObjectCfg | DeformableObjectCfg = MISSING
# Table
table = AssetBaseCfg(
......@@ -88,7 +88,7 @@ class ActionsCfg:
"""Action specifications for the MDP."""
# will be set by agent env cfg
arm_action: mdp.JointPositionActionCfg = MISSING
arm_action: mdp.JointPositionActionCfg | mdp.DifferentialInverseKinematicsActionCfg = MISSING
gripper_action: mdp.BinaryJointPositionActionCfg = MISSING
......
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