Skip to content

Commit a3e0f7c

Browse files
committed
[optimize] optimize GPU pipeline efficiency by indexing GPU tensor first, consider asset_option use_mesh_materials
1 parent 02f8bcf commit a3e0f7c

File tree

4 files changed

+10
-11
lines changed

4 files changed

+10
-11
lines changed

example/isaacgym/run_isaacgym_viz.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,11 +32,11 @@ def wrapped_create_sim(self: vec_task.VecTask, compute_device: int, graphics_dev
3232
vec_task.VecTask.create_sim = wrapped_create_sim
3333

3434
# Create web visualizer
35-
create_isaac_visualizer(port=6000, host="localhost", keep_default_viewer=True, max_env=1)
35+
create_isaac_visualizer(port=6000, host="localhost", keep_default_viewer=True, max_env=4)
3636

3737
# Create the environment and step the simulation as normal
3838
device = "cuda" # or "cpu"
39-
num_env = 2
39+
num_env = 8
4040
rl_device = device
4141
envs = isaacgymenvs.make(
4242
seed=0,

sim_web_visualizer/base_visualizer_client.py

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,6 @@ def add_default_scene_elements(self):
3939
self.viz["/Lights/AmbientLight/<object>"].set_property("intensity", 0.8)
4040
self.viz["/Lights/PointLightNegativeX"].delete()
4141
self.viz["/Lights/PointLightPositiveX"].delete()
42-
# self.viz["/Lights/PointLightNegativeX/<object>"].set_property("intensity", 1)
43-
# TODO: cast shadow does not work
44-
# self.viz["/Lights/PointLightNegativeX/<object>"].set_property("castShadow", False)
4542

4643
def delete_all(self):
4744
print("Deleting all previous scene asset.")
@@ -50,10 +47,11 @@ def delete_all(self):
5047

5148
@staticmethod
5249
def dry_load_asset(filename, collapse_fixed_joints: bool,
53-
replace_cylinder_with_capsule=False) -> AssetResource:
50+
replace_cylinder_with_capsule=False, use_mesh_materials=False) -> AssetResource:
5451
if filename.endswith(".urdf"):
5552
resource = load_urdf_with_yourdfpy(filename, collapse_fixed_joints,
56-
replace_cylinder_with_capsule=replace_cylinder_with_capsule)
53+
replace_cylinder_with_capsule=replace_cylinder_with_capsule,
54+
use_mesh_materials=use_mesh_materials)
5755
elif filename.endswith(".xml"):
5856
resource = load_mjcf_with_dmc(filename, collapse_fixed_joints)
5957
else:

sim_web_visualizer/isaac_visualizer_client.py

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -128,7 +128,8 @@ def load_asset(sim: gymapi.Sim, rootpath: str, filename: str,
128128
# Load asset into the memory as asset resource but not forward it into the web viewer
129129
# The asset will only be loaded into web viewer after a `create_actor` call
130130
resource = self.dry_load_asset(filename, collapse_fixed_joints,
131-
replace_cylinder_with_capsule=options.replace_cylinder_with_capsule)
131+
replace_cylinder_with_capsule=options.replace_cylinder_with_capsule,
132+
use_mesh_materials=options.use_mesh_materials)
132133
self.asset_resource_map[id(asset)] = resource
133134
return asset
134135

@@ -353,7 +354,7 @@ def draw_viewer(viewer: Union[MimicViewer, gymapi.Viewer], sim: gymapi.Sim, rend
353354

354355
if USE_GPU_PIPELINE:
355356
self.original_gym.refresh_rigid_body_state_tensor(self.sim)
356-
rigid_body_state = self.rigid_body_state_tensor.cpu().numpy()[:len(self.env_map), :, :7]
357+
rigid_body_state = self.rigid_body_state_tensor[:len(self.env_map), :, :7].cpu().numpy()
357358
pos = rigid_body_state[:, :, :3]
358359
quat = np.concatenate([rigid_body_state[..., 6:7], rigid_body_state[..., 3:6]], axis=-1) # xyzw -> wxyz
359360
qs = quaternion.as_quat_array(quat)

sim_web_visualizer/parser/urdf.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616

1717

1818
def load_urdf_with_yourdfpy(urdf_path: str, collapse_fixed_joints: bool,
19-
replace_cylinder_with_capsule=False) -> AssetResource:
19+
replace_cylinder_with_capsule=False, use_mesh_materials=False) -> AssetResource:
2020
robot = urdf.URDF.load(urdf_path)
21-
material_map = robot._material_map
21+
material_map = robot._material_map if not use_mesh_materials else {}
2222

2323
# Dry run data for faster loading
2424
offline_data_dict = {}

0 commit comments

Comments
 (0)