生成多个资产#
典型的生成配置(在 生成基本物体到场景中 教程中介绍)复制相同的资产(或 USD 基元)到不同的已解析的基元路径表达式中。例如,如果用户指定要在 “/World/Table_.*/Object” 生成资产,则相同的资产将在路径 “/World/Table_0/Object” 、 “/World/Table_1/Object” 等处创建。
但有时,可能希望在基元路径下生成不同的资产,以确保模拟的多样性。本指南介绍了如何使用生成功能在每个基元路径下创建不同的资产。
示例脚本 multi_asset.py
用作参考,位于 IsaacLab/source/standalone/demos
目录中。
multi_asset.py 的代码
1# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
2# All rights reserved.
3#
4# SPDX-License-Identifier: BSD-3-Clause
5
6"""This script demonstrates how to spawn multiple objects in multiple environments.
7
8.. code-block:: bash
9
10 # Usage
11 ./isaaclab.sh -p source/standalone/demos/multi_asset.py --num_envs 2048
12
13"""
14
15from __future__ import annotations
16
17"""Launch Isaac Sim Simulator first."""
18
19
20import argparse
21
22from omni.isaac.lab.app import AppLauncher
23
24# add argparse arguments
25parser = argparse.ArgumentParser(description="Demo on spawning different objects in multiple environments.")
26parser.add_argument("--num_envs", type=int, default=1024, help="Number of environments to spawn.")
27# append AppLauncher cli args
28AppLauncher.add_app_launcher_args(parser)
29# parse the arguments
30args_cli = parser.parse_args()
31
32# launch omniverse app
33app_launcher = AppLauncher(args_cli)
34simulation_app = app_launcher.app
35
36"""Rest everything follows."""
37
38import random
39
40import omni.usd
41from pxr import Gf, Sdf
42
43import omni.isaac.lab.sim as sim_utils
44from omni.isaac.lab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg
45from omni.isaac.lab.scene import InteractiveScene, InteractiveSceneCfg
46from omni.isaac.lab.sim import SimulationContext
47from omni.isaac.lab.utils import Timer, configclass
48from omni.isaac.lab.utils.assets import ISAACLAB_NUCLEUS_DIR
49
50##
51# Pre-defined Configuration
52##
53
54from omni.isaac.lab_assets.anymal import ANYDRIVE_3_LSTM_ACTUATOR_CFG # isort: skip
55
56
57##
58# Randomization events.
59##
60
61
62def randomize_shape_color(prim_path_expr: str):
63 """Randomize the color of the geometry."""
64 # acquire stage
65 stage = omni.usd.get_context().get_stage()
66 # resolve prim paths for spawning and cloning
67 prim_paths = sim_utils.find_matching_prim_paths(prim_path_expr)
68 # manually clone prims if the source prim path is a regex expression
69 with Sdf.ChangeBlock():
70 for prim_path in prim_paths:
71 # spawn single instance
72 prim_spec = Sdf.CreatePrimInLayer(stage.GetRootLayer(), prim_path)
73
74 # DO YOUR OWN OTHER KIND OF RANDOMIZATION HERE!
75 # Note: Just need to acquire the right attribute about the property you want to set
76 # Here is an example on setting color randomly
77 color_spec = prim_spec.GetAttributeAtPath(prim_path + "/geometry/material/Shader.inputs:diffuseColor")
78 color_spec.default = Gf.Vec3f(random.random(), random.random(), random.random())
79
80
81##
82# Scene Configuration
83##
84
85
86@configclass
87class MultiObjectSceneCfg(InteractiveSceneCfg):
88 """Configuration for a multi-object scene."""
89
90 # ground plane
91 ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())
92
93 # lights
94 dome_light = AssetBaseCfg(
95 prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
96 )
97
98 # rigid object
99 object: RigidObjectCfg = RigidObjectCfg(
100 prim_path="/World/envs/env_.*/Object",
101 spawn=sim_utils.MultiAssetSpawnerCfg(
102 assets_cfg=[
103 sim_utils.ConeCfg(
104 radius=0.3,
105 height=0.6,
106 visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2),
107 ),
108 sim_utils.CuboidCfg(
109 size=(0.3, 0.3, 0.3),
110 visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2),
111 ),
112 sim_utils.SphereCfg(
113 radius=0.3,
114 visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0), metallic=0.2),
115 ),
116 ],
117 random_choice=True,
118 rigid_props=sim_utils.RigidBodyPropertiesCfg(
119 solver_position_iteration_count=4, solver_velocity_iteration_count=0
120 ),
121 mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
122 collision_props=sim_utils.CollisionPropertiesCfg(),
123 ),
124 init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 2.0)),
125 )
126
127 # articulation
128 robot: ArticulationCfg = ArticulationCfg(
129 prim_path="/World/envs/env_.*/Robot",
130 spawn=sim_utils.MultiUsdFileCfg(
131 usd_path=[
132 f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd",
133 f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd",
134 ],
135 random_choice=True,
136 rigid_props=sim_utils.RigidBodyPropertiesCfg(
137 disable_gravity=False,
138 retain_accelerations=False,
139 linear_damping=0.0,
140 angular_damping=0.0,
141 max_linear_velocity=1000.0,
142 max_angular_velocity=1000.0,
143 max_depenetration_velocity=1.0,
144 ),
145 articulation_props=sim_utils.ArticulationRootPropertiesCfg(
146 enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0
147 ),
148 activate_contact_sensors=True,
149 ),
150 init_state=ArticulationCfg.InitialStateCfg(
151 pos=(0.0, 0.0, 0.6),
152 joint_pos={
153 ".*HAA": 0.0, # all HAA
154 ".*F_HFE": 0.4, # both front HFE
155 ".*H_HFE": -0.4, # both hind HFE
156 ".*F_KFE": -0.8, # both front KFE
157 ".*H_KFE": 0.8, # both hind KFE
158 },
159 ),
160 actuators={"legs": ANYDRIVE_3_LSTM_ACTUATOR_CFG},
161 )
162
163
164##
165# Simulation Loop
166##
167
168
169def run_simulator(sim: SimulationContext, scene: InteractiveScene):
170 """Runs the simulation loop."""
171 # Extract scene entities
172 # note: we only do this here for readability.
173 rigid_object = scene["object"]
174 robot = scene["robot"]
175 # Define simulation stepping
176 sim_dt = sim.get_physics_dt()
177 count = 0
178 # Simulation loop
179 while simulation_app.is_running():
180 # Reset
181 if count % 500 == 0:
182 # reset counter
183 count = 0
184 # reset the scene entities
185 # object
186 root_state = rigid_object.data.default_root_state.clone()
187 root_state[:, :3] += scene.env_origins
188 rigid_object.write_root_state_to_sim(root_state)
189 # robot
190 # -- root state
191 root_state = robot.data.default_root_state.clone()
192 root_state[:, :3] += scene.env_origins
193 robot.write_root_state_to_sim(root_state)
194 # -- joint state
195 joint_pos, joint_vel = robot.data.default_joint_pos.clone(), robot.data.default_joint_vel.clone()
196 robot.write_joint_state_to_sim(joint_pos, joint_vel)
197 # clear internal buffers
198 scene.reset()
199 print("[INFO]: Resetting scene state...")
200
201 # Apply action to robot
202 robot.set_joint_position_target(robot.data.default_joint_pos)
203 # Write data to sim
204 scene.write_data_to_sim()
205 # Perform step
206 sim.step()
207 # Increment counter
208 count += 1
209 # Update buffers
210 scene.update(sim_dt)
211
212
213def main():
214 """Main function."""
215 # Load kit helper
216 sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device)
217 sim = SimulationContext(sim_cfg)
218 # Set main camera
219 sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0])
220
221 # Design scene
222 scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0, replicate_physics=False)
223 with Timer("[INFO] Time to create scene: "):
224 scene = InteractiveScene(scene_cfg)
225
226 with Timer("[INFO] Time to randomize scene: "):
227 # DO YOUR OWN OTHER KIND OF RANDOMIZATION HERE!
228 # Note: Just need to acquire the right attribute about the property you want to set
229 # Here is an example on setting color randomly
230 randomize_shape_color(scene_cfg.object.prim_path)
231
232 # Play the simulator
233 sim.reset()
234 # Now we are ready!
235 print("[INFO]: Setup complete...")
236 # Run the simulator
237 run_simulator(sim, scene)
238
239
240if __name__ == "__main__":
241 # run the main execution
242 main()
243 # close sim app
244 simulation_app.close()
此脚本创建多个环境,每个环境都有一个刚性对象,可以是圆锥、立方体或球体,以及一个分别是 ANYmal-C 或 ANYmal-D 机器人的关节。
使用多资产生成功能#
可以使用生成器 MultiAssetSpawnerCfg
和 MultiUsdFileCfg
在每个环境中生成不同的资产和 USDs:
我们将
RigidObjectCfg
中的生成配置设置为MultiAssetSpawnerCfg
:object: RigidObjectCfg = RigidObjectCfg( prim_path="/World/envs/env_.*/Object", spawn=sim_utils.MultiAssetSpawnerCfg( assets_cfg=[ sim_utils.ConeCfg( radius=0.3, height=0.6, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2), ), sim_utils.CuboidCfg( size=(0.3, 0.3, 0.3), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2), ), sim_utils.SphereCfg( radius=0.3, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0), metallic=0.2), ), ], random_choice=True, rigid_props=sim_utils.RigidBodyPropertiesCfg( solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ), init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 2.0)), )
此函数允许您定义可以作为刚性对象生成的不同资产的列表。当
random_choice
设置为 True 时,将从列表中随机选择一个资产,并在指定的基元路径上生成它。类似地,我们将
ArticulationCfg
中的生成配置设置为MultiUsdFileCfg
:robot: ArticulationCfg = ArticulationCfg( prim_path="/World/envs/env_.*/Robot", spawn=sim_utils.MultiUsdFileCfg( usd_path=[ f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd", f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd", ], random_choice=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 ), activate_contact_sensors=True, ), init_state=ArticulationCfg.InitialStateCfg( pos=(0.0, 0.0, 0.6), joint_pos={ ".*HAA": 0.0, # all HAA ".*F_HFE": 0.4, # both front HFE ".*H_HFE": -0.4, # both hind HFE ".*F_KFE": -0.8, # both front KFE ".*H_KFE": 0.8, # both hind KFE }, ), actuators={"legs": ANYDRIVE_3_LSTM_ACTUATOR_CFG}, )
与之前类似,此配置允许选择代表关节资产的不同 USD 文件。
需要注意的事项#
相似的资产结构#
在使用相同的物理接口(刚性对象或关节类)生成和处理多个资产时,必须确保所有基元路径上的资产遵循相似的结构。对于关节来说,这意味着它们都必须具有相同数量的链接和关节、相同数量的碰撞体,以及相同的名称。如果不是这种情况,基元的物理解析可能会受到影响并且失败。
此功能的主要目的是使用户能够创建相同资产的随机版本,例如具有不同链接长度的机器人,或具有不同碰撞器形状的刚性对象。
在交互式场景中禁用物理复制#
默认情况下,标志 scene.InteractiveScene.replicate_physics
被设置为 True。此标志告知物理引擎模拟环境是彼此的副本,因此只需解析第一个环境即可了解整个模拟场景。这有助于加快模拟场景的解析速度。
但是,在不同环境中生成不同的资产的情况下,这一假设不再成立。因此,必须禁用标志 scene.InteractiveScene.replicate_physics
。
# Design scene
scene_cfg = MultiObjectSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0, replicate_physics=False)
with Timer("[INFO] Time to create scene: "):
scene = InteractiveScene(scene_cfg)
代码执行#
要执行带有多个环境和随机资产的脚本,请使用以下命令:
./isaaclab.sh -p source/standalone/demos/multi_asset.py --num_envs 2048
此命令运行具有 2048 个环境的模拟场景,每个环境都具有随机选择的资产。要停止模拟,可以关闭窗口或在终端中按下 Ctrl+C
。