@@ -378,123 +378,6 @@ def update_visibility(self, visible: bool, frame: int):
378
378
self .usd_prim .GetAttribute ("visibility" ).Set ("invisible" , frame )
379
379
380
380
381
- class USDPrimitive :
382
-
383
- def __init__ (
384
- self ,
385
- stage : Usd .Stage ,
386
- geom : mujoco .MjvGeom ,
387
- obj_name : str ,
388
- rgba : np .ndarray = np .array ([1 , 1 , 1 , 1 ]),
389
- texture_file : Optional [str ] = None ,
390
- ):
391
- self .stage = stage
392
- self .geom = geom
393
- self .obj_name = obj_name
394
- self .rgba = rgba
395
- self .texture_file = texture_file
396
-
397
- self .usd_prim = Usd .Prim ()
398
- self .usd_primitive_shape = Usd .PrimitiveShape ()
399
- self .transform_op = Usd .TransformOp ()
400
-
401
- def _set_refinement_properties (self ):
402
- self .usd_prim .GetAttribute ("subdivisionScheme" ).Set ("none" )
403
-
404
- def _attach_material (self ):
405
- mtl_path = Sdf .Path (f"/World/_materials/Material_{ self .obj_name } " )
406
- mtl = UsdShade .Material .Define (self .stage , mtl_path )
407
- if self .texture_file :
408
- bsdf_shader = UsdShade .Shader .Define (
409
- self .stage , mtl_path .AppendPath ("Principled_BSDF" )
410
- )
411
- image_shader = UsdShade .Shader .Define (
412
- self .stage , mtl_path .AppendPath ("Image_Texture" )
413
- )
414
- uvmap_shader = UsdShade .Shader .Define (
415
- self .stage , mtl_path .AppendPath ("uvmap" )
416
- )
417
-
418
- # settings the bsdf shader attributes
419
- bsdf_shader .CreateIdAttr ("UsdPreviewSurface" )
420
- bsdf_shader .CreateInput (
421
- "diffuseColor" , Sdf .ValueTypeNames .Color3f
422
- ).ConnectToSource (image_shader .ConnectableAPI (), "rgb" )
423
- bsdf_shader .CreateInput ("opacity" , Sdf .ValueTypeNames .Float ).Set (
424
- float (self .rgba [- 1 ])
425
- )
426
- bsdf_shader .CreateInput ("metallic" , Sdf .ValueTypeNames .Float ).Set (
427
- self .geom .shininess
428
- )
429
- bsdf_shader .CreateInput ("roughness" , Sdf .ValueTypeNames .Float ).Set (
430
- 1.0 - self .geom .shininess
431
- )
432
-
433
- mtl .CreateSurfaceOutput ().ConnectToSource (
434
- bsdf_shader .ConnectableAPI (), "surface"
435
- )
436
-
437
- self .usd_primitive_shape .GetPrim ().ApplyAPI (UsdShade .MaterialBindingAPI )
438
- UsdShade .MaterialBindingAPI (self .usd_primitive_shape ).Bind (mtl )
439
-
440
- # setting the image texture attributes
441
- image_shader .CreateIdAttr ("UsdUVTexture" )
442
- image_shader .CreateInput ("file" , Sdf .ValueTypeNames .Asset ).Set (
443
- self .texture_file
444
- )
445
- image_shader .CreateInput (
446
- "sourceColorSpace" , Sdf .ValueTypeNames .Token
447
- ).Set ("sRGB" )
448
- image_shader .CreateInput ("st" , Sdf .ValueTypeNames .Float2 ).ConnectToSource (
449
- uvmap_shader .ConnectableAPI (), "result"
450
- )
451
- image_shader .CreateOutput ("rgb" , Sdf .ValueTypeNames .Float3 )
452
-
453
- # setting uvmap shader attributes
454
- uvmap_shader .CreateIdAttr ("UsdPrimvarReader_float2" )
455
- uvmap_shader .CreateInput ("varname" , Sdf .ValueTypeNames .Token ).Set ("UVMap" )
456
- uvmap_shader .CreateOutput ("results" , Sdf .ValueTypeNames .Float2 )
457
- else :
458
- bsdf_shader = UsdShade .Shader .Define (
459
- self .stage , mtl_path .AppendPath ("Principled_BSDF" )
460
- )
461
-
462
- # settings the bsdf shader attributes
463
- bsdf_shader .CreateIdAttr ("UsdPreviewSurface" )
464
- bsdf_shader .CreateInput ("diffuseColor" , Sdf .ValueTypeNames .Color3f ).Set (
465
- tuple (self .rgba [:3 ])
466
- )
467
- bsdf_shader .CreateInput ("opacity" , Sdf .ValueTypeNames .Float ).Set (
468
- float (self .rgba [- 1 ])
469
- )
470
- bsdf_shader .CreateInput ("metallic" , Sdf .ValueTypeNames .Float ).Set (
471
- self .geom .shininess
472
- )
473
- bsdf_shader .CreateInput ("roughness" , Sdf .ValueTypeNames .Float ).Set (
474
- 1.0 - self .geom .shininess
475
- )
476
-
477
- mtl .CreateSurfaceOutput ().ConnectToSource (
478
- bsdf_shader .ConnectableAPI (), "surface"
479
- )
480
-
481
- self .usd_primitive_shape .GetPrim ().ApplyAPI (UsdShade .MaterialBindingAPI )
482
- UsdShade .MaterialBindingAPI (self .usd_primitive_shape ).Bind (mtl )
483
-
484
- def update (self , pos : np .ndarray , mat : np .ndarray , visible : bool , frame : int ):
485
- transformation_mat = mujoco .usd_util .create_transform_matrix (
486
- rotation_matrix = mat , translation_vector = pos
487
- ).T
488
- self .transform_op .Set (Gf .Matrix4d (transformation_mat .tolist ()), frame )
489
- self .update_visibility (visible , frame )
490
-
491
- def update_visibility (self , visible : bool , frame : int ):
492
- if visible :
493
- self .usd_prim .GetAttribute ("visibility" ).Set ("inherited" , frame )
494
- else :
495
- self .usd_prim .GetAttribute ("visibility" ).Set ("invisible" , frame )
496
-
497
-
498
381
class USDCapsule (USDPrimitive ):
499
382
500
383
def __init__ (
@@ -522,7 +405,7 @@ def __init__(
522
405
self ._set_size_attributes ()
523
406
self ._attach_material ()
524
407
525
- self ._set_refinement_properties ()
408
+ # self._set_refinement_properties()
526
409
527
410
def _set_size_attributes (self ):
528
411
self .usd_primitive_shape .GetRadiusAttr ().Set (float (self .geom .size [0 ]))
@@ -558,7 +441,7 @@ def __init__(
558
441
self ._set_size_attributes ()
559
442
self ._attach_material ()
560
443
561
- self ._set_refinement_properties ()
444
+ # self._set_refinement_properties()
562
445
563
446
def _set_size_attributes (self ):
564
447
self .scale_op .Set (Gf .Vec3d (self .geom .size .tolist ()))
@@ -849,7 +732,7 @@ def __init__(self, stage: Usd.Stage, obj_name: str):
849
732
850
733
def update (self , cam_pos : np .ndarray , cam_mat : np .ndarray , frame : int ):
851
734
852
- transformation_mat = mujoco .usd_util .create_transform_matrix (
735
+ transformation_mat = mujoco .usd . utils .create_transform_matrix (
853
736
rotation_matrix = cam_mat , translation_vector = cam_pos
854
737
).T
855
738
self .transform_op .Set (Gf .Matrix4d (transformation_mat .tolist ()), frame )
0 commit comments