2222parser = argparse .ArgumentParser (description = "Benchmark loading different robots." )
2323parser .add_argument ("--num_envs" , type = int , default = 32 , help = "Number of robots to simulate." )
2424parser .add_argument (
25- "--robot" ,
26- type = str ,
27- choices = [' anymal_d' , 'h1' , 'g1' ],
25+ "--robot" ,
26+ type = str ,
27+ choices = [" anymal_d" , "h1" , "g1" ],
2828 default = "h1" ,
2929 help = "Choose which robot to load: anymal_d, h1, or g1." ,
3030)
6969
7070print (f"[INFO]: Imports time: { (imports_time_end - imports_time_begin ) / 1e6 :.2f} ms" )
7171
72+
7273@configclass
7374class RobotSceneCfg (InteractiveSceneCfg ):
7475 """Configuration for a simple scene with a robot."""
@@ -91,25 +92,23 @@ class RobotSceneCfg(InteractiveSceneCfg):
9192 else :
9293 raise ValueError (f"Unsupported robot type: { args_cli .robot } ." )
9394
95+
9496def run_simulator (sim : sim_utils .SimulationContext , scene : InteractiveScene ):
9597 """Runs the simulation loop."""
9698 # Extract scene entities
9799 # note: we only do this here for readability.
98100 robot = scene ["robot" ]
99101 # Define simulation stepping
100102 sim_dt = sim .get_physics_dt ()
101- count = 0
102103
103104 # Start the timer for creating the scene
104105 step_time_begin = time .perf_counter_ns ()
105106 num_steps = 2000
106107
107108 # Simulation loop
108- for _ in range (num_steps ):
109+ for count in range (num_steps ):
109110 # Reset
110111 if count % 500 == 0 :
111- # reset counter
112- count = 0
113112 # reset the scene entities
114113 # root state
115114 # we offset the root state by the origin since the states are written in simulation world frame
@@ -132,11 +131,9 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
132131 scene .write_data_to_sim ()
133132 # Perform step
134133 sim .step ()
135- # Increment counter
136- count += 1
137134 # Update buffers
138135 scene .update (sim_dt )
139-
136+
140137 # Stop the timer for reset
141138 step_time_end = time .perf_counter_ns ()
142139 print (f"[INFO]: Per step time: { (step_time_end - step_time_begin ) / num_steps / 1e6 :.2f} ms" )
@@ -149,7 +146,7 @@ def main():
149146 sim = SimulationContext (sim_cfg )
150147 # Set main camera
151148 sim .set_camera_view ([2.5 , 0.0 , 4.0 ], [0.0 , 0.0 , 2.0 ])
152-
149+
153150 # Start the timer for creating the scene
154151 setup_time_begin = time .perf_counter_ns ()
155152 # Design scene
0 commit comments