-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
e4d7e9f
commit adc0b64
Showing
2 changed files
with
38 additions
and
20 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,32 +1,50 @@ | ||
"""Test script for the simulator.""" | ||
|
||
import argparse | ||
import time | ||
import asyncio | ||
|
||
from kscale import K | ||
|
||
from kos_sim.simulator import MujocoSimulator | ||
|
||
|
||
def test_simulation(model_path: str, duration: float = 5.0, speed: float = 1.0, render: bool = True) -> None: | ||
simulator = MujocoSimulator(model_path, render=render) | ||
async def test_simulation(model_name: str, duration: float = 5.0, speed: float = 1.0, render: bool = True) -> None: | ||
api = K() | ||
bot_dir = await api.download_and_extract_urdf(model_name) | ||
bot_mjcf = next(bot_dir.glob("*.mjcf")) | ||
|
||
simulator = MujocoSimulator(bot_mjcf, render=render) | ||
|
||
timestep = simulator.timestep | ||
initial_update = last_update = asyncio.get_event_loop().time() | ||
|
||
while True: | ||
current_time = asyncio.get_event_loop().time() | ||
if current_time - initial_update > duration: | ||
break | ||
|
||
sim_time = current_time - last_update | ||
last_update = current_time | ||
while sim_time > 0: | ||
simulator.step() | ||
sim_time -= timestep | ||
|
||
for _ in range(int(duration / 0.001)): | ||
simulator.step() | ||
time.sleep(0.001) | ||
simulator.render() | ||
|
||
simulator.close() | ||
|
||
|
||
def main() -> None: | ||
async def main() -> None: | ||
parser = argparse.ArgumentParser(description="Test the MuJoCo simulation.") | ||
parser.add_argument("--model-path", type=str, required=True, help="Path to MuJoCo XML model file") | ||
parser.add_argument("model_name", type=str, help="Name of the model to simulate") | ||
parser.add_argument("--duration", type=float, default=5.0, help="Duration to run simulation (seconds)") | ||
parser.add_argument("--speed", type=float, default=1.0, help="Simulation speed multiplier") | ||
parser.add_argument("--no-render", action="store_true", help="Disable rendering") | ||
|
||
args = parser.parse_args() | ||
test_simulation(args.model_path, duration=args.duration, speed=args.speed, render=not args.no_render) | ||
await test_simulation(args.model_name, duration=args.duration, speed=args.speed, render=not args.no_render) | ||
|
||
|
||
if __name__ == "__main__": | ||
# python -m kos_sim.test_simulator | ||
main() | ||
asyncio.run(main()) |