Closed H-Hisamichi closed 2 months ago
The error is correct for what is says. You're registering a lot more rigid body materials than what PhysX can handle. You'd need to simplify the randomization probably (i.e. reduce number of physics materials made).
Can you share more information on your setup?
Hi, @Mayankm96
Thank you for the advice. I hadn't considered that randomization might be the cause.
GPU: NVIDIA RTX A4000 16GB
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from future import annotations
import torch
import omni.isaac.lab.sim as sim_utils from omni.isaac.lab.assets import Articulation, ArticulationCfg from omni.isaac.lab.envs import DirectRLEnv, DirectRLEnvCfg from omni.isaac.lab.scene import InteractiveSceneCfg from omni.isaac.lab.sensors import ContactSensor, ContactSensorCfg, RayCaster, RayCasterCfg, patterns from omni.isaac.lab.sim import SimulationCfg, PhysxCfg from omni.isaac.lab.terrains import TerrainImporterCfg from omni.isaac.lab.utils import configclass, math from pxr import PhysxSchema
from omni.isaac.lab_assets.hr_v2 import HR_CFG # isort: skip from omni.isaac.lab.terrains.config.rough import ROUGH_TERRAINS_CFG # isort: skip import omni.isaac.core.utils.transformations as transformations_utils from torch.utils.tensorboard import SummaryWriter from omni.isaac.lab.sim.spawners import RigidObjectSpawnerCfg
@configclass class HexapodFlatEnvCfg(DirectRLEnvCfg):
episode_length_s = 20.0
decimation = 4
action_scale = 1.0
servo1_action_scale = 0.3
num_actions = 18
num_observations = 33
num_states = 0
# simulation
sim: SimulationCfg = SimulationCfg(
dt=1 / 200,
render_interval=decimation,
disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
static_friction=1.0,
dynamic_friction=1.0,
restitution=0.0,
),
)
terrain = TerrainImporterCfg(
prim_path="/World/ground",
terrain_type="plane",
collision_group=-1,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
static_friction=1.0,
dynamic_friction=1.0,
restitution=0.0,
),
debug_vis=False,
)
physx_config = sim_utils.PhysxCfg(
gpu_temp_buffer_capacity=2**24,
gpu_max_rigid_patch_count=20*2**15,
gpu_heap_capacity=2**26,
gpu_collision_stack_size=2**26
)
# scene
scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=2048, env_spacing=4.0, replicate_physics=True) # dif: 4096
# robot
RigidObjectSpawnerCfg(activate_contact_sensors=True)
robot: ArticulationCfg = HR_CFG.replace(prim_path="/World/envs/env_.*/Robot")
contact_sensor = ContactSensorCfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/Robot/.*Arm3", history_length=3, update_period=0.005, track_air_time=True
)
# reward scales
lin_vel_reward_scale = 2.0
yaw_rate_reward_scale = 0.5
z_vel_reward_scale = -2.0
#ang_vel_reward_scale = -0.05
joint_torque_reward_scale = -2.5e-6
joint_accel_reward_scale = -2.5e-8
action_rate_reward_scale = -0.001
feet_air_time_reward_scale = 0.5
undersired_contact_reward_scale = -1.0
flat_orientation_reward_scale = 5.0
positive_contact_reward_scale = 1.0 # add
keep_circular_reward_scale = 0.5 # add
angular_rate_reward_scale = 5.0 # add
rotation_angle_reward_scale = 10 # add
fall_down_reward_scale = 1.0 # add
body_pos_reward_scale = 2.0 # add
ang_vel_reward_scale = 7.0 # add
joint_pos_reward_scale = 2.0 # add
body_ang_vel_reward_scale = 7.0 # add
projected_gravity_xy = 2.0 # add
z_displacement_reward_scale = 2.0 # add
@configclass class HexapodRoughEnvCfg(HexapodFlatEnvCfg):
num_observations = 235
terrain = TerrainImporterCfg(
prim_path="/World/ground",
terrain_type="generator",
terrain_generator=ROUGH_TERRAINS_CFG,
max_init_terrain_level=9,
collision_group=-1,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
static_friction=1.0,
dynamic_friction=1.0,
),
visual_material=sim_utils.MdlFileCfg(
mdl_path="{NVIDIA_NUCLEUS_DIR}/Materials/Base/Architecture/Shingles_01.mdl",
project_uvw=True,
),
debug_vis=False,
)
flat_orientation_reward_scale = 0.0
class HexapodEnv(DirectRLEnv): cfg: HexapodFlatEnvCfg | HexapodRoughEnvCfg
def __init__(self, cfg: HexapodFlatEnvCfg | HexapodRoughEnvCfg, render_mode: str | None = None, **kwargs):
super().__init__(cfg, render_mode, **kwargs)
def get_env_local_pose(env_pos: torch.Tensor, xformable: UsdGeom.Xformable, device: torch.device):
world_transform = xformable.ComputeLocalToWorldTransform(0)
world_pos = world_transform.ExtractTranslation()
world_quat = world_transform.ExtractRotationQuat()
print(f"world_pos: {world_pos}")
self._actions = torch.zeros(self.num_envs, self.cfg.num_actions, device=self.device)
self._previous_actions = torch.zeros(self.num_envs, self.cfg.num_actions, device=self.device)
# X/Y linear velocity and yaw angular velocity commands
self._commands = torch.zeros(self.num_envs, 1, device=self.device)
# Definition of the target speed default tensor. Details are set in _reset_idx.
# Logging
self._episode_sums = {
key: torch.zeros(self.num_envs, dtype=torch.float, device=self.device)
for key in [
#"track_lin_vel_xy_exp",
"track_body_pos_z_exp",
#"z_displacement",
"track_body_ang_vel_exp",
"track_gravity_xy_exp",
#"track_joint_pos_exp",
#"positive_contact_reward",
"dof_torques_l2",
"dof_acc_l2",
"action_rate_l2",
"body_ang_vel_l2"
#"flat_orientation_l2",
#"fall_down_reward",
#"keep_circular",
#"angular_rate_reward",
#"rotation_angle_reward"
]
}
self._feet_ids, _ = self._contact_sensor.find_bodies(".*Arm3")
# Randomize robot friction
env_ids = self._robot._ALL_INDICES
mat_props = self._robot.root_physx_view.get_material_properties()
mat_props[:, :, :2].uniform_(0.6, 0.8)
self._robot.root_physx_view.set_material_properties(mat_props, env_ids.cpu())
# Randomize base mass
base_id, _ = self._robot.find_bodies(".*Arm3")
masses = self._robot.root_physx_view.get_masses()
masses[:, base_id] += torch.zeros_like(masses[:, base_id]).uniform_(1.0, 5.0)
self._robot.root_physx_view.set_masses(masses, env_ids.cpu())
# create auxiliary variables for computing applied action, observations and rewards
soft_joint_pos_limits = self._robot.data.soft_joint_pos_limits.clone()
self.joint1_dof_limits = soft_joint_pos_limits[0, 0, :]
self.joint2_3_dof_limits = soft_joint_pos_limits[0, 6, :]
main_body_ang_vel_vec_w = self._robot.data.body_ang_vel_w[:, 0, :]
self.main_body_ang_vel = torch.norm(main_body_ang_vel_vec_w, dim=-1)
def _setup_scene(self):
self._robot = Articulation(self.cfg.robot)
self.scene.articulations["robot"] = self._robot
self._contact_sensor = ContactSensor(self.cfg.contact_sensor)
self.scene.sensors["contact_sensor"] = self._contact_sensor
self.cfg.terrain.num_envs = self.scene.cfg.num_envs
self.cfg.terrain.env_spacing = self.scene.cfg.env_spacing
self._terrain = self.cfg.terrain.class_type(self.cfg.terrain)
# clone, filter, and replicate
self.scene.clone_environments(copy_from_source=False)
self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path])
# add lights
light_cfg = sim_utils.DomeLightCfg(intensity=2000.0, color=(0.75, 0.75, 0.75))
light_cfg.func("/World/Light", light_cfg)
def _pre_physics_step(self, actions: torch.Tensor):
self._actions = actions.clone()# / 2.9 #.clamp(-0.17, 0.17)
self._processed_actions = self.cfg.action_scale * self._actions + self._robot.data.default_joint_pos
def _apply_action(self):
clamped_actions = self._processed_actions.clone()
clamped_actions[:, 0:6] *= self.cfg.servo1_action_scale
clamped_actions[:, 0:6] = torch.clamp(clamped_actions[:, 0:6], self.joint1_dof_limits[0], self.joint1_dof_limits[1])
clamped_actions[:, 6:18] = torch.clamp(clamped_actions[:, 6:18], self.joint2_3_dof_limits[0], self.joint2_3_dof_limits[1])
self._robot.set_joint_position_target(clamped_actions)
def _get_observations(self) -> dict:
self._previous_actions = self._actions.clone()
net_contact_forces = self._contact_sensor.data.net_forces_w_history
contact = torch.max(torch.norm(net_contact_forces[:, :, self._feet_ids], dim=-1), dim=1)[0]
flat_orientation = torch.sum(torch.square(self._robot.data.projected_gravity_b[:, :2]), dim=1).view(-1, 1)
obs = torch.cat(
[
tensor
for tensor in (
#self._robot.data.root_lin_vel_b,
self._robot.data.root_ang_vel_b,
self._robot.data.root_quat_w,
#self._robot.data.body_pos_w[:, 0, :],
flat_orientation,
#self._robot.data.body_quat_w,
self._commands,
#joint_pos - default_joint_pos,
#self._robot.data.joint_pos - self._robot.data.default_joint_pos,
#joint_vel,
#self._robot.data.joint_vel,
#height_data,
#actions,
self._actions,
contact
)
if tensor is not None
],
dim=-1,
)
observations = {"policy": obs}
#print(f"obs: {obs}")
return observations
def _get_rewards(self) -> torch.Tensor:
# linear velocity tracking
#lin_vel_error = torch.sum(torch.square(self._commands[:, :2] - self._robot.data.root_lin_vel_b[:, :2]), dim=1)
#lin_vel_error_mapped = torch.exp(-lin_vel_error / 0.25)
# pos tracking(z)
# self._robot.data.default_root_state[:, 2:3]: tensor([[0.3600],[0.3600]], device='cuda:0')
# self._robot.data.root_pos_w[:, 2:3]: tensor([[0.4705],[0.3229]], device='cuda:0')
body_pos_error = torch.sum(torch.square(self._robot.data.default_root_state[:, 2:3] - self._robot.data.root_pos_w[:, 2:3]), dim=1)
body_pos_error_mapped = -(1 - torch.exp(-body_pos_error / 0.001))
# suppresses displacement in the Z-axis direction
#z_displacement = self._robot.data.root_pos_w[:, 2:3] - self._robot.data.default_root_state[:, 2:3]
#z_displacement = torch.where(z_displacement < 0, torch.tensor(0.0, device='cuda:0'), z_displacement)
#z_displacement_neg = -torch.abs(z_displacement)
#z_displacement_reward = z_displacement_neg.view(-1)
# angular velocuty tracking
_commands = self._commands.clone()
# self._commands: tensor([[ 4.4577],[-3.3919]], device='cuda:0')
# self._robot.data.root_ang_vel_b[:, -1:]: tensor([[-0.1698],[-0.2068]], device='cuda:0')
ang_vel_error = torch.sum(torch.square(_commands - self._robot.data.root_ang_vel_b[:, -1:]), dim=1)
ang_vel_error_mapped = torch.exp(-ang_vel_error / 10)
mask = torch.all(_commands == self._robot.data.root_ang_vel_b[:, -1:], dim=1)
ang_vel_error_mapped[mask] = 100
# projected gravity xy tracking
# self._robot.data.projected_gravity_b[:, :2]: tensor([[-0.0052, -0.9990],[-0.0501, -0.9933]], device='cuda:0')
neg_rew_scale = 0.5
flat_orientation = torch.sum(torch.square(self._robot.data.projected_gravity_b[:, :2]), dim=1)
flat_orientation_error = torch.square(1.0 - flat_orientation)
flat_orientation_error_mapped = -(1 - torch.exp(-flat_orientation_error / 0.04))
#flat_orientation_neg_rew = -(1 - flat_orientation_error_mapped)
#flat_orientation_error_mapped += flat_orientation_neg_rew * neg_rew_scale
#print(f"flat_orientation_error_mapped: {flat_orientation_error_mapped}")
# joint torques
joint_torques = torch.sum(torch.square(self._robot.data.applied_torque), dim=1)
# joint acceleration
joint_accel = torch.sum(torch.square(self._robot.data.joint_acc), dim=1)
# action rate
action_rate = torch.sum(torch.square(self._actions - self._previous_actions), dim=1)
# body angular velocity
# Recommendation of rotation and control of target reverse rotation.
body_ang_vel = self._robot.data.root_ang_vel_b[:, -1]
#body_ang_vel = torch.clamp(abs(body_ang_vel), min=0.0, max=262.0)
# self._commands: tensor([[ 4.4577],[-3.3919]], device='cuda:0')
# self._robot.data.root_ang_vel_b[:, -1:]: tensor([[-0.1588],[-0.7619]], device='cuda:0')
#_commands = self._commands.clone()
#result = torch.where(
# torch.sign(self._robot.data.root_ang_vel_b[:, -1:]) != torch.sign(_commands),
# -torch.abs(self._robot.data.root_ang_vel_b[:, -1:]),
# torch.abs(self._robot.data.root_ang_vel_b[:, -1:]) * 2.0
#)
#body_ang_vel = torch.squeeze(result)
rewards = {
#"track_lin_vel_xy_exp": lin_vel_error_mapped * self.cfg.lin_vel_reward_scale * self.step_dt,
"track_body_pos_z_exp": body_pos_error_mapped * self.cfg.body_pos_reward_scale * self.step_dt,
#"z_displacement": z_displacement_reward * self.cfg.z_displacement_reward_scale * self.step_dt,
"track_body_ang_vel_exp": ang_vel_error_mapped * self.cfg.ang_vel_reward_scale * self.step_dt,
"track_gravity_xy_exp": flat_orientation_error_mapped * self.cfg.projected_gravity_xy * self.step_dt,
#"track_joint_pos_exp": joint_pos_error_mapped * self.cfg.joint_pos_reward_scale * self.step_dt,
#"positive_contact_reward": contacts * self.cfg.positive_contact_reward_scale * self.step_dt,
"dof_torques_l2": joint_torques * self.cfg.joint_torque_reward_scale * self.step_dt,
"dof_acc_l2": joint_accel * self.cfg.joint_accel_reward_scale * self.step_dt,
"action_rate_l2": action_rate * self.cfg.action_rate_reward_scale * self.step_dt,
"body_ang_vel_l2": body_ang_vel * self.cfg.body_ang_vel_reward_scale * self.step_dt
#"flat_orientation_l2": flat_orientation * self.cfg.flat_orientation_reward_scale * self.step_dt,
#"fall_down_reward": fall_down * self.cfg.fall_down_reward_scale * self.step_dt,
#"keep_circular": circular_rewards * self.cfg.keep_circular_reward_scale * self.step_dt,
#"angular_rate_reward": ang_val_rewards * self.cfg.angular_rate_reward_scale * self.step_dt,
#"rotation_angle_reward": local_rot_rewards * self.cfg.rotation_angle_reward_scale * self.step_dt
}
reward = torch.sum(torch.stack(list(rewards.values())), dim=0)
# Logging
for key, value in rewards.items():
self._episode_sums[key] += value
return reward
def _get_dones(self) -> tuple[torch.Tensor, torch.Tensor]:
time_out = self.episode_length_buf >= self.max_episode_length - 1
flat_orientation = torch.sum(torch.square(self._robot.data.projected_gravity_b[:, :2]), dim=1)
main_body_ang_vel = self.main_body_ang_vel.clone()
# End condition according to rotation angle.
processed_rows = torch.empty((0,), device='cuda:0')
default_body_pos = torch.tensor([0.5, 0.5, 0.5, 0.5], device='cuda:0')
current_pos = self._robot.data.body_quat_w[:, 0, :]
for row in current_pos:
rotated_ang = math.quat_error_magnitude(default_body_pos, row)
processed_rows = torch.cat((processed_rows, rotated_ang.unsqueeze(0)))
# If the rotation rotation around the Z-axis exceeds 0.79 radians, it will terminate.
root_quat_w = self._robot.data.root_quat_w
default_root_state = self._robot.data.default_root_state[:, 3:7]
default_root_state_inv = math.quat_inv(default_root_state)
local_rot_amt = math.quat_mul(default_root_state_inv, root_quat_w)
local_rot_amt_euler = math.euler_xyz_from_quat(local_rot_amt)
died = (flat_orientation < 0.5) #| (main_body_ang_vel > 8) | (processed_rows > 0.7854) | (local_rot_amt_euler[0] > 0.7854)
#print(f"died: {died}")
return died, time_out
def _reset_idx(self, env_ids: torch.Tensor | None):
if env_ids is None or len(env_ids) == self.num_envs:
env_ids = self._robot._ALL_INDICES
self._robot.reset(env_ids)
super()._reset_idx(env_ids)
if len(env_ids) == self.num_envs:
# Spread out the resets to avoid spikes in training when many environments reset at a similar time
self.episode_length_buf[:] = torch.randint_like(self.episode_length_buf, high=int(self.max_episode_length))
self._actions[env_ids] = 0.0
self._previous_actions[env_ids] = 0.0
# Sample new commands
self._commands[env_ids] = torch.zeros_like(self._commands[env_ids]).uniform_(-4.57, 4.57) #def: uniform_(-1.0, 1.0)
# Reset robot state
joint_pos = self._robot.data.default_joint_pos[env_ids]
joint_vel = self._robot.data.default_joint_vel[env_ids]
default_root_state = self._robot.data.default_root_state[env_ids]
default_root_state[:, :3] += self._terrain.env_origins[env_ids]
self._robot.write_root_pose_to_sim(default_root_state[:, :7], env_ids)
self._robot.write_root_velocity_to_sim(default_root_state[:, 7:], env_ids)
self._robot.write_joint_state_to_sim(joint_pos, joint_vel, None, env_ids)
# Logging
extras = dict()
for key in self._episode_sums.keys():
episodic_sum_avg = torch.mean(self._episode_sums[key][env_ids])
extras["Episode Reward/" + key] = episodic_sum_avg / self.max_episode_length_s
self._episode_sums[key][env_ids] = 0.0
self.extras["log"] = dict()
self.extras["log"].update(extras)
extras = dict()
extras["Episode Termination/base_contact"] = torch.count_nonzero(self.reset_terminated[env_ids]).item()
extras["Episode Termination/time_out"] = torch.count_nonzero(self.reset_time_outs[env_ids]).item()
self.extras["log"].update(extras)
This code is based on the Direct Workflow for anymal_c that comes with IsaacLab.
- Here are the PPO settings:
params: seed: 42
env: clip_actions: 1.0
algo: name: a2c_continuous
model: name: continuous_a2c_logstd
network: name: actor_critic separate: False space: continuous: mu_activation: None sigma_activation: None
mu_init:
name: default
sigma_init:
name: const_initializer
val: 0
fixed_sigma: True
mlp:
units: [128, 128, 128]
activation: elu
d2rl: False
initializer:
name: default
regularizer:
name: None
load_checkpoint: False # flag which sets whether to load the checkpoint load_path: '' # path to the checkpoint to load
config: name: anymal_c_flat env_name: rlgpu device: 'cuda:0' device_name: 'cuda:0' multi_gpu: False ppo: True mixed_precision: True normalize_input: False normalize_value: True value_bootstrap: True num_actors: -1 # configured from the script (based on num_envs) reward_shaper: scale_value: 0.6 normalize_advantage: True gamma: 0.99 tau: 0.95 learning_rate: 1e-3 lr_schedule: adaptive schedule_type: legacy kl_threshold: 0.01 score_to_win: 20000 max_epochs: 5000 save_best_after: 100 save_frequency: 50 grad_norm: 1.0 entropy_coef: 0.005 truncate_grads: True e_clip: 0.2 horizon_length: 24
minibatch_size: 49152
mini_epochs: 5
critic_coef: 2.0
clip_value: True
seq_length: 4
bounds_loss_coef: 0.0
Additional information.
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the Mujoco Ant robot."""
from future import annotations
import omni.isaac.lab.sim as sim_utils from omni.isaac.lab.actuators import ImplicitActuatorCfg from omni.isaac.lab.assets import ArticulationCfg from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR import torch import numpy as np from omni.isaac.lab.utils.math import quat_from_angle_axis, quat_mul
angles_y = torch.tensor([1.5708], dtype=torch.float32) axes_y = torch.tensor([[0, 1, 0]], dtype=torch.float32) angles_z = torch.tensor([1.5708], dtype=torch.float32) axes_z = torch.tensor([[0, 0, 1]], dtype=torch.float32) quaternions_y = quat_from_angle_axis(angles_y, axes_y) quaternions_z = quat_from_angle_axis(angles_z, axes_z) quaternions = quat_mul(quaternions_y, quaternions_z) numpy_array = quaternions.numpy()
formatted_tuple = tuple(float(f"{val:.4f}") for val in numpy_array[0]) print(f"formatted_tuple: {formatted_tuple}")
HR_CFG = ArticulationCfg( prim_path="{ENV_REGEX_NS}/Robot", spawn=sim_utils.UsdFileCfg(
#usd_path="/home/robot/hisamichi/IsaacSim/IsaacSim_HexapodBody_simplification_v1.usd",
usd_path="/home/robot/hisamichi/IsaacSim/IsaacSim_HexapodBody_simple_v2.usd",
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False, # add
linear_damping=0.0, # add
angular_damping=0.0, # add
max_linear_velocity=1000.0, # add
max_angular_velocity=1000.0, # add
max_depenetration_velocity=1.0,
#enable_gyroscopic_forces=True,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
solver_position_iteration_count=4,
solver_velocity_iteration_count=0,
#fix_root_link=True,
#sleep_threshold=0.005,
#stabilization_threshold=0.001,
),
copy_from_source=False,
activate_contact_sensors=True, # add
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.36),
rot=formatted_tuple,
joint_pos={
"Leg1RevJoint1":0.0, "Leg2RevJoint1":0.0, "Leg3RevJoint1":0.0, "Leg4RevJoint1":0.0, "Leg5RevJoint1":0.0, "Leg6RevJoint1":0.0,
"Leg1RevJoint2":1.71, "Leg2RevJoint2":1.71, "Leg3RevJoint2":1.71, "Leg4RevJoint2":1.71, "Leg5RevJoint2":1.71, "Leg6RevJoint2":1.71,
"Leg1RevJoint3":-2.195, "Leg2RevJoint3":-2.195, "Leg3RevJoint3":-2.195, "Leg4RevJoint3":-2.195, "Leg5RevJoint3":-2.195, "Leg6RevJoint3":-2.195
},
),
actuators={
"Leg": ImplicitActuatorCfg(
joint_names_expr=["Leg.*RevJoint.*"],
stiffness=None,
damping=None,
),
},
)
The issue arises in the following section of your code:
# Randomize robot friction
env_ids = self._robot._ALL_INDICES
mat_props = self._robot.root_physx_view.get_material_properties()
mat_props[:, :, :2].uniform_(0.6, 0.8)
self._robot.root_physx_view.set_material_properties(mat_props, env_ids.cpu())
# Randomize base mass
base_id, _ = self._robot.find_bodies(".*Arm3")
masses = self._robot.root_physx_view.get_masses()
masses[:, base_id] += torch.zeros_like(masses[:, base_id]).uniform_(1.0, 5.0)
self._robot.root_physx_view.set_masses(masses, env_ids.cpu())
It seems like you're using a direct environment, and this problem is not fully handled in this method. However, if you look at the manager-based randomization in the this line in events, you’ll notice that the randomization process is handled differently there. So as error said the original method of randomizing material properties using PhysX might hit the 64k material limit. To handle this, we need to use a bucketing mechanism. Material properties are divided into 64 buckets, and the values are assigned by binning the randomized values into these buckets.
To address this issue, you can modify the code as follows:
# Get body ids
self._body_ids, _ = self._robot.find_bodies(self._robot.body_names)
# Randomize robot friction
env_ids = self._robot._ALL_INDICES.cpu()
mat_props = self._robot.root_physx_view.get_material_properties()
mat_props[:, :, :2].uniform_(0.6, 0.8)
lo = torch.tensor([0.6, 0.8, 0.0], device="cpu")
hi = torch.tensor([0.6, 0.8, 0.0], device="cpu")
material_samples = torch.zeros(mat_props[env_ids].shape)
# to avoid 64k material limit in physx, we bucket materials by binning randomized material properties
# into buckets based on the number of buckets specified
for d in range(3):
buckets = torch.tensor([(hi[d] - lo[d]) * i / 64 + lo[d] for i in range(64)], device="cpu")
material_samples[..., d] = buckets[torch.searchsorted(buckets, material_samples[..., d].contiguous()) - 1]
# update material buffer with new samples
# obtain number of shapes per body (needed for indexing the material properties correctly)
# note: this is a workaround since the Articulation does not provide a direct way to obtain the number of shapes
# per body. We use the physics simulation view to obtain the number of shapes per body.
num_shapes_per_body = []
materials = self._robot.root_physx_view.get_material_properties()
for link_path in self._robot.root_physx_view.link_paths[0]:
link_physx_view = self._robot._physics_sim_view.create_rigid_body_view(link_path) # type: ignore
num_shapes_per_body.append(link_physx_view.max_shapes)
# sample material properties from the given ranges
for body_id in self._body_ids:
# start index of shape
start_idx = sum(num_shapes_per_body[:body_id])
# end index of shape
end_idx = start_idx + num_shapes_per_body[body_id]
# assign the new materials
# material ids are of shape: num_env_ids x num_shapes
# material_buckets are of shape: num_buckets x 3
materials[env_ids, start_idx:end_idx] = material_samples[:, start_idx:end_idx]
self._robot.root_physx_view.set_material_properties(mat_props, env_ids.cpu())
# Randomize base mass
base_id, _ = self._robot.find_bodies("base")
masses = self._robot.root_physx_view.get_masses()
masses[:, base_id] += torch.zeros_like(masses[:, base_id]).uniform_(-5.0, 5.0)
self._robot.root_physx_view.set_masses(masses, env_ids.cpu())
We used the same solution that used in events.py
. For simplicity of sharing code here, the number 64
is hardcoded as the number of buckets. You can make this a configurable parameter in your code.
Hi, @Mayankm96 , @MiladShafiee
Thank you everyone for your help. I managed to resolve the error, and I really appreciate your support.
On a slightly different note, I came across something in the documentation under the Simulation Config
section. The code snippet physx: PhysxCfg = PhysxCfg()
seems like it might be a syntax error, so I thought I’d mention it.
@H-Hisamichi Great to hear that, so the problem was 64k material limit in physx,
? and solved with bucketing materials? If yes I may open a MR to add it to the Anymal Direct Demo
@MiladShafiee
Yes, that's correct. After modifying the randomization part of my code following your advice, the '64k material limit in PhysX' error was resolved.
As for the buffer overflow error, I was able to fix it by implementing the following code:
(physx = sim_utils.PhysxCfg(gpu_max_rigid_patch_count=2**24
, which resolved the issue by adjusting the GPU's rigid patch count.)
class HexapodFlatEnvCfg(DirectRLEnvCfg):
# env
episode_length_s = 20.0
decimation = 4
action_scale = 1.0
servo1_action_scale = 0.3
num_actions = 18
num_observations = 33
num_states = 0
# simulation
sim: SimulationCfg = SimulationCfg(
dt=1 / 200,
render_interval=decimation,
disable_contact_processing=True,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
static_friction=1.0,
dynamic_friction=1.0,
restitution=0.0,
),
physx = sim_utils.PhysxCfg(
gpu_max_rigid_patch_count=2**24
)
)
terrain = TerrainImporterCfg(
prim_path="/World/ground",
terrain_type="plane",
collision_group=-1,
physics_material=sim_utils.RigidBodyMaterialCfg(
friction_combine_mode="multiply",
restitution_combine_mode="multiply",
static_friction=1.0,
dynamic_friction=1.0,
restitution=0.0,
),
debug_vis=False,
)
Ok great thanks @H-Hisamichi .
Hi @Mayankm96, What do you think about adding these corrections to Anymal-C Direct Demo? It seems other direct environments not having randomization and not using set_material_properties
.
Yes definitely. @kellyguo11 for vis.
I was just about to open a pull request that I saw you had already submitted one. Thank you so much.
Question
Hello everyone, I’m encountering some issues while running reinforcement learning experiments in IsaacLab with large agent counts, specifically when using more than 107 agents. Here’s a summary of the problem:
When using fewer than 107 agents, everything works fine, and I can run the reinforcement learning without any issues. It seems the errors are related to PhysX material limits and buffer overflows. Has anyone experienced similar issues with high agent counts in IsaacLab or any other PhysX-based environments? Are there any recommendations for increasing the material or buffer limits to handle larger simulations? I’ve already tried adjusting
gpu_max_rigid_patch_count
, but the errors persist.Thanks in advance for your help!