Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -115,3 +115,4 @@ output
.cursor/
artifacts/
nohup/
.omx/
141 changes: 141 additions & 0 deletions AGENTS.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,141 @@
# AGENTS.md

This file defines repository-level development rules for people and AI agents working in this repo.

The goals are:
- keep the repo simple and easy to read
- prefer local consistency over clever abstractions
- follow existing project infrastructure instead of inventing parallel workflows

For testing infrastructure details, also refer to:
- [docs/source/metasim/developer_guide/autotest.md](./docs/source/metasim/developer_guide/autotest.md)
- https://roboverse.wiki/metasim/developer_guide/autotest
- [ENVIRONMENTS.md](./ENVIRONMENTS.md)

## General Development Rules

### Keep Changes Small And Local

- Prefer modifying existing files over adding new files.
- Do not introduce a new helper/module/doc file when an existing one already owns that responsibility.
- Do not add architectural layers or abstractions unless the current code clearly needs them.
- If a change can be expressed as a small local fix, prefer that over a framework-style refactor.

### Preserve Existing User-Facing Contracts

- Do not silently change public semantics when the repo already has established behavior.
- When broadening a base contract, make sure concrete subclasses actually satisfy it.
- If a behavior is only compatibility support, document it as such instead of treating it as a primary contract.

### Be Explicit About Scope

- Only test simulators that are related to or influenced by the current change.
- If the correct simulator env mapping is not known from repo context or user instructions, ask before running simulator-backed tests.
- Do not claim “all tests pass” unless the exact requested test commands were actually run in the correct envs.

### Prefer Fail-Fast Over Silent Degradation

- For unsupported backends or unsupported code paths, prefer an explicit error over silent success.
- Do not turn an explicit unsupported-operation failure into a silent no-op unless there is a strong reason.

## Testing Rules For `metasim/test`

### Source Of Truth

The authoritative test workflow is the MetaSim autotest guide:
- [docs/source/metasim/developer_guide/autotest.md](./docs/source/metasim/developer_guide/autotest.md)

When there is any doubt about pytest structure, markers, suite registration, handler reuse, or backend-specific commands, follow that guide.

### Test Discovery And File Format

For files under `metasim/test`:

- Test file names should start with `test_` or end with `_test.py`.
- Test function names should start with `test_`.
- Helper functions should not start with `test_`.
- Test directories that participate in the shared suite/registration system must contain `__init__.py`.
- If a suite uses the shared `handler` fixture, its package or file prefix must be registered through `register_shared_suite(...)` in the relevant `conftest.py`.

### Markers And Fixtures

Use the existing marker model described in the autotest guide:

- `@pytest.mark.mujoco`
- `@pytest.mark.isaacgym`
- `@pytest.mark.isaacsim`
- `@pytest.mark.newton`
- `@pytest.mark.mjx`
- `@pytest.mark.sim(...)`
- `@pytest.mark.general`

Rules:

- `@pytest.mark.general` tests should not request the `handler` fixture.
- Simulator-backed tests should use the repo’s shared fixture/registration system instead of custom one-off setup.
- Prefer extending an existing relevant test file under `metasim/test` before creating a new one.

### Backend-Specific Autotest Commands

When running tests for `metasim/test`, use these commands in the corresponding conda envs:

```bash
# MuJoCo only
pytest metasim/test/ -k mujoco

# IsaacGym (use entry script for proper import order)
python metasim/test/isaacgym_entry.py metasim/test/ -k isaacgym

# IsaacSim only
pytest metasim/test/ -k isaacsim

# Newton only
pytest metasim/test/ -k newton

# General tests (no simulator)
pytest metasim/test/ -k general
```

### Environment Correspondence

Read simulator-to-conda-env mapping from [ENVIRONMENTS.md](./ENVIRONMENTS.md).

### Test Selection Rule

- Only run a simulator’s tests when current changes affect that simulator or shared code used by it.
- For shared code changes, run the relevant backend tests one-by-one, not through improvised filtering logic unless necessary.
- Always consider whether `general` tests should also be run for the changed area.
- Run simulator-specific tests in an environment where the simulator can access a usable GPU when that backend expects or requires GPU execution.
- Do not claim simulator-backed tests were meaningfully exercised if the backend failed only because GPU access was unavailable.

### IsaacGym Special Rule

- For IsaacGym-backed tests, use:
`python metasim/test/isaacgym_entry.py ...`
- Do not replace it with plain `pytest ... -k isaacgym`, because the import order is part of the required test harness.

### GPU Rule For Simulator Tests

- `isaacgym`, `isaacsim`, and `newton` test runs should be treated as GPU-backed simulator tests unless there is clear repo-specific evidence that a given run is intended to be CPU-only.
- Before relying on simulator-backed test results, verify that the selected env can actually see a GPU.
- If GPU access is missing, report that as an environment blocker instead of treating the run as a normal simulator test result.

## AI-Agent Rules

### Before Changing Code

- Read the relevant existing code paths first.
- Read the existing test file for the area before adding a new test.
- If the change touches testing infrastructure or simulator-specific behavior, check `docs/source/metasim/developer_guide/autotest.md`.

### Before Adding Files

- Ask: can this be done by extending an existing file cleanly?
- If yes, do that instead.
- New files should be the exception, not the default.

### Before Declaring Success

- Say exactly what was verified.
- If tests were blocked by environment problems, say so explicitly and include the real blocker.
- Do not compress environment/setup failures into “test failures” without explanation.
3 changes: 3 additions & 0 deletions CLAUDE.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# CLAUDE.md

Follow the repository development and testing rules in [AGENTS.md](./AGENTS.md).
17 changes: 17 additions & 0 deletions ENVIRONMENTS.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# ENVIRONMENTS.md

This file defines the local environment correspondence for simulator-backed development and testing.

Update it when the actual conda env names on the machine differ from the defaults below.

## Simulator Environment Correspondence

- `isaacgym` -> conda env `isaacgym`
- `mujoco` -> conda env `isaacgym`
- `newton` -> conda env `newton`
- `isaacsim` -> conda env `isaacsim`

## Notes

- Keep this file simple and human-editable.
- If a simulator env is unknown or not configured, ask the user before running simulator-backed tests.
4 changes: 2 additions & 2 deletions get_started/10_mount_camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -253,7 +253,7 @@ def __post_init__(self):
}
]
handler.set_states(init_states)
obs = handler.get_states()
obs = handler.get_states(mode="tensor")
os.makedirs("get_started/output", exist_ok=True)


Expand Down Expand Up @@ -282,7 +282,7 @@ def __post_init__(self):
]
handler.set_dof_targets(actions)
handler.simulate()
obs = handler.get_states()
obs = handler.get_states(mode="tensor")
obs_saver.add(obs)
step += 1

Expand Down
2 changes: 1 addition & 1 deletion get_started/7_multiple_robots.py
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ def main():

# Save observations for video
if obs_saver is not None:
states = handler.get_states()
states = handler.get_states(mode="tensor")
obs_saver.add(states)

step += 1
Expand Down
2 changes: 1 addition & 1 deletion get_started/9_cfg_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ def main():
# Save observations for video
if obs_saver is not None:
try:
raw_states = env.task_env.handler.get_states() # Access the underlying simulator
raw_states = env.task_env.handler.get_states(mode="tensor") # Access the underlying simulator
obs_saver.add(raw_states)
except Exception as e:
log.debug(f"Could not get camera data: {e}")
Expand Down
2 changes: 1 addition & 1 deletion get_started/motion_planning/0_franka_planning.py
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ def move_to_pose(
robot_joint_limits = scenario.robots[0].joint_limits
for step in range(4):
log.debug(f"Step {step}")
states = handler.get_states()
states = handler.get_states(mode="tensor")
rotation_transform_for_franka = torch.tensor(
[
[0.0, 0.0, 1.0],
Expand Down
2 changes: 1 addition & 1 deletion get_started/motion_planning/1_object_grasping.py
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ def move_to_pose(
robot_joint_limits = scenario.robots[0].joint_limits
for step in range(1):
log.debug(f"Step {step}")
states = handler.get_states()
states = handler.get_states(mode="tensor")
curr_robot_q = states.robots[robot.name].joint_pos[:, inverse_reorder_idx].cuda()

pcd = get_point_cloud_from_obs(obs)
Expand Down
2 changes: 1 addition & 1 deletion get_started/motion_planning/2_water_pouring.py
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ def move_to_pose(
robot_joint_limits = scenario.robots[0].joint_limits
for step in range(1):
log.debug(f"Step {step}")
states = handler.get_states()
states = handler.get_states(mode="tensor")
curr_robot_q = states.robots[robot.name].joint_pos[:, inverse_reorder_idx].cuda()

gripper_out = torch.tensor([1, 0, 0])
Expand Down
2 changes: 1 addition & 1 deletion get_started/multiple_cameras.py
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ def __post_init__(self):
}
]
handler.set_states(init_states)
obs = handler.get_states()
obs = handler.get_states(mode="tensor")
os.makedirs("get_started/output", exist_ok=True)
save_path = f"get_started/output/multiple_cameras_{args.sim}.png"
log.info(f"Saving image to {save_path}")
Expand Down
4 changes: 2 additions & 2 deletions get_started/rl/0_ppo.py
Original file line number Diff line number Diff line change
Expand Up @@ -207,14 +207,14 @@ def train_ppo():

# inference
obs = env_inference.reset()
obs_orin = env_inference.env.handler.get_states()
obs_orin = env_inference.env.handler.get_states(mode="tensor")
obs_saver.add(obs_orin)

for _ in range(250):
actions, _ = model.predict(obs, deterministic=True)
env_inference.step_async(actions)
obs, _, _, _ = env_inference.step_wait()
obs_orin = env_inference.env.handler.get_states()
obs_orin = env_inference.env.handler.get_states(mode="tensor")
obs_saver.add(obs_orin)

# obs_saver.save()
Expand Down
4 changes: 2 additions & 2 deletions get_started/rl/0_ppo_gym_style.py
Original file line number Diff line number Diff line change
Expand Up @@ -227,15 +227,15 @@ def train_ppo():

# inference
obs = env_inference.reset()
obs_orin = env_inference.gym_vec.task_env.handler.get_states()
obs_orin = env_inference.gym_vec.task_env.handler.get_states(mode="tensor")
obs_saver.add(obs_orin)

for _ in range(250):
actions, _ = model.predict(obs, deterministic=True)
env_inference.step_async(actions)
obs, _, _, _ = env_inference.step_wait()

obs_orin = env_inference.gym_vec.task_env.handler.get_states()
obs_orin = env_inference.gym_vec.task_env.handler.get_states(mode="tensor")
obs_saver.add(obs_orin)

obs_saver.save()
Expand Down
4 changes: 2 additions & 2 deletions get_started/rl/fast_td3/1_fttd3.py
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ def render_with_rollout() -> list:
# Initialize video recording
os.makedirs("get_started/output/rl", exist_ok=True)
obs_saver = ObsSaver(video_path=f"get_started/output/rl/1_fttd3_{simulator}.mp4")
obs_orin = env.handler.get_states()
obs_orin = env.handler.get_states(mode="tensor")
obs_saver.add(obs_orin)

for _ in range(env.max_episode_steps):
Expand All @@ -324,7 +324,7 @@ def render_with_rollout() -> list:
obs, _, terminated, time_out, _ = env.step(actions.float())
done = terminated | time_out

obs_orin = env.handler.get_states()
obs_orin = env.handler.get_states(mode="tensor")
obs_saver.add(obs_orin)
if done.any():
break
Expand Down
2 changes: 1 addition & 1 deletion metasim/example/control_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ def __post_init__(self):
for _ in range(scenario.num_envs)
]
flatten_obs, reward, terminated, time_out, info = env.step(actions)
raw_obs = env.handler.get_states()
raw_obs = env.handler.get_states(mode="tensor")
obs_saver.add(raw_obs)
step += 1

Expand Down
8 changes: 4 additions & 4 deletions metasim/example/replay_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ def main(): # noqa: D103
obs, _ = env.reset()
saver_act.add(obs)

captured_states.append(env.handler.get_states())
captured_states.append(env.handler.get_states(mode="tensor"))

step = 0
while True:
Expand All @@ -177,9 +177,9 @@ def main(): # noqa: D103
saver_act.add(obs)

try:
captured_states.append(env.handler.get_states())
captured_states.append(env.handler.get_states(mode="tensor"))
except Exception:
captured_states.append(env.handler.get_states())
captured_states.append(env.handler.get_states(mode="tensor"))

if success.any():
log.info(f"[ACT] Env {success.nonzero().squeeze(-1).tolist()} succeeded!")
Expand Down Expand Up @@ -210,7 +210,7 @@ def main(): # noqa: D103
env.handler.set_states(states_i)

env.handler.refresh_render()
obs = env.handler.get_states()
obs = env.handler.get_states(mode="tensor")
saver_state.add(obs)

try:
Expand Down
1 change: 1 addition & 0 deletions metasim/queries/contact_force.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ def bind_handler(self, handler: BaseSimHandler, *args, **kwargs):
if self.simulator in ["isaacgym", "mujoco"]:
self.body_ids_reindex = handler._get_body_ids_reindex(self.robots[0].name)
elif self.simulator == "isaacsim":
self.handler.init_contact_sensor(self.robots[0].name)
sorted_body_names = self.handler.get_body_names(self.robots[0].name, True)
self.body_ids_reindex = torch.tensor(
[self.handler.contact_sensor.body_names.index(name) for name in sorted_body_names],
Expand Down
39 changes: 2 additions & 37 deletions metasim/randomization/scene_randomizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
from metasim.randomization.base import BaseRandomizerType
from metasim.randomization.core.object_registry import ObjectMetadata, ObjectRegistry
from metasim.utils.configclass import configclass
from metasim.utils.isaacsim_asset_util import convert_urdf_to_usd_cached

# =============================================================================
# Scene Element Configurations
Expand Down Expand Up @@ -938,44 +939,8 @@ def _convert_urdf_to_usd(self, urdf_path: str) -> str | None:
Returns:
Path to converted USD file, or None if failed
"""
from pathlib import Path

try:
urdf_path_obj = Path(urdf_path)
usd_output = urdf_path_obj.parent / (urdf_path_obj.stem + ".usd")

# If already converted, use existing
if usd_output.exists():
return str(usd_output)

logger.info(f"Converting URDF to USD: {urdf_path}")

# Use AssetConverterFactory with MESH source type
try:
from generation.asset_converter import AssetConverterFactory
from generation.enums import AssetType

converter = AssetConverterFactory.create(
target_type=AssetType.USD,
source_type=AssetType.MESH, # KEY: MESH not URDF!
simulation_app=None, # Already running
exit_close=False,
force_usd_conversion=True,
make_instanceable=True,
)

converter.convert(str(urdf_path), str(usd_output))

if not usd_output.exists():
logger.error(f"USD not created: {usd_output}")
return None

logger.info(f"Converted: {usd_output}")
return str(usd_output)

except Exception as e:
logger.error(f"Conversion failed: {e}")
return None
return convert_urdf_to_usd_cached(urdf_path)

except Exception as e:
logger.error(f"URDF conversion error: {e}")
Expand Down
Loading