Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Adding logic for custom cameras in USD #2400

Open
wants to merge 9 commits into
base: main
Choose a base branch
from
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
18 changes: 17 additions & 1 deletion python/mujoco/testdata/usd_golden.usda
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ def Xform "World"
def Xform "Light_Xform_0"
{
double3 xformOp:translate.timeSamples = {
0: (0, -3.674234628677368, 3.674234628677368),
0: (0, -6, 0),
}
uniform token[] xformOpOrder = ["xformOp:translate"]

Expand All @@ -28,6 +28,22 @@ def Xform "World"
}
}

def Xform "Camera_Xform_primary_camera"
{
matrix4d xformOp:transform.timeSamples = {
0: ( (1, 0, -0, 0), (0, 0.009999499656260014, 0.9999499917030334, 0), (0, -0.9999499917030334, 0.009999499656260014, 0), (0, -6, 0, 1) ),
}
uniform token[] xformOpOrder = ["xformOp:transform"]

def Camera "Camera_primary_camera"
{
float2 clippingRange = (0.0001, 1000000)
float focalLength = 12
float focusDistance = 400
float horizontalAperture = 12
}
}

def Xform "Camera_Xform_closeup"
{
matrix4d xformOp:transform.timeSamples = {
Expand Down
13 changes: 8 additions & 5 deletions python/mujoco/usd/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
# ==============================================================================
"""Camera handling for USD exporter."""

from typing import List, Optional, Tuple

import mujoco.usd.utils as utils_module

import numpy as np
Expand All @@ -24,15 +26,16 @@
from pxr import Usd
from pxr import UsdGeom

import mujoco.usd.utils as utils_module

class USDCamera:
"""Class that handles the cameras in the USD scene."""

def __init__(self, stage: Usd.Stage, obj_name: str):
"""Class that handles the cameras in the USD scene"""
def __init__(self, stage: Usd.Stage, camera_name: str):
self.stage = stage

xform_path = f"/World/Camera_Xform_{obj_name}"
camera_path = f"{xform_path}/Camera_{obj_name}"
xform_path = f"/World/Camera_Xform_{camera_name}"
camera_path = f"{xform_path}/Camera_{camera_name}"
self.usd_xform = UsdGeom.Xform.Define(stage, xform_path)
self.usd_camera = UsdGeom.Camera.Define(stage, camera_path)
self.usd_prim = stage.GetPrimAtPath(camera_path)
Expand Down
6 changes: 4 additions & 2 deletions python/mujoco/usd/demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,16 +31,18 @@ def generate_usd_trajectory(local_args):
# create an instance of the USDExporter
exp = exporter.USDExporter(
model=m,
output_directory_name=pathlib.Path(local_args.model_path).stem,
output_directory=pathlib.Path(local_args.model_path).stem,
output_directory_root=local_args.output_directory_root,
camera_names=local_args.camera_names,
)

cam = mujoco.MjvCamera()

# step through the simulation for the given duration of time
while d.time < local_args.duration:
mujoco.mj_step(m, d)
if exp.frame_count < d.time * local_args.framerate:
exp.update_scene(data=d)
exp.update_scene(data=d, camera=cam)

exp.add_light(pos=(0, 0, 0),
intensity=2000,
Expand Down
Loading