@@ -522,7 +522,12 @@ class FileMorph(Morph):
522522 coacd_options : CoacdOptions, optional
523523 Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
524524 parse_glb_with_zup : bool, optional
525- Whether to use zup to load glb files. Defaults to False.
525+ This parameter is deprecated, see file_meshes_are_zup.
526+ file_meshes_are_zup : bool, optional
527+ Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
528+ as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
529+ where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
530+ This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
526531 visualization : bool, optional
527532 Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
528533 purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -549,7 +554,8 @@ class FileMorph(Morph):
549554 decompose_robot_error_threshold : float = float ("inf" )
550555 coacd_options : Optional [CoacdOptions ] = None
551556 recompute_inertia : bool = False
552- parse_glb_with_zup : bool = False
557+ parse_glb_with_zup : Optional [bool ] = None
558+ file_meshes_are_zup : bool = True
553559 batch_fixed_verts : bool = False
554560
555561 def __init__ (self , ** data ):
@@ -569,6 +575,13 @@ def __init__(self, **data):
569575 "'convexify' and 'decompose_(robot|object)_error_threshold' instead."
570576 )
571577
578+ if self .parse_glb_with_zup is not None :
579+ self .file_meshes_are_zup = not self .parse_glb_with_zup
580+ gs .logger .warning (
581+ "FileMorph option 'parse_glb_with_zup' is deprecated and will be removed in future release. Please use "
582+ "'file_meshes_are_zup'instead."
583+ )
584+
572585 # Make sure that this threshold is positive to avoid decomposition of convex and primitive shapes
573586 self .decompose_object_error_threshold = max (self .decompose_object_error_threshold , gs .EPS )
574587 self .decompose_robot_error_threshold = max (self .decompose_robot_error_threshold , gs .EPS )
@@ -668,7 +681,12 @@ class Mesh(FileMorph, TetGenMixin):
668681 parse_glb_with_trimesh : bool, optional
669682 Whether to use trimesh to load glb files. Defaults to False, in which case pygltflib will be used.
670683 parse_glb_with_zup : bool, optional
671- Whether to use zup to load glb files. Defaults to False.
684+ This parameter is deprecated, see file_meshes_are_zup.
685+ file_meshes_are_zup : bool, optional
686+ Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
687+ as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
688+ where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
689+ This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
672690 fixed : bool, optional
673691 Whether the object should be fixed. Defaults to False. **This is only used for RigidEntity.**
674692 batch_fixed_verts : bool, optional
@@ -799,7 +817,12 @@ class MJCF(FileMorph):
799817 coacd_options : CoacdOptions, optional
800818 Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
801819 parse_glb_with_zup : bool, optional
802- Whether to use zup to load glb files. Defaults to False.
820+ This parameter is deprecated, see file_meshes_are_zup.
821+ file_meshes_are_zup : bool, optional
822+ Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
823+ as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
824+ where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
825+ This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
803826 visualization : bool, optional
804827 Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
805828 purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -905,7 +928,12 @@ class URDF(FileMorph):
905928 coacd_options : CoacdOptions, optional
906929 Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
907930 parse_glb_with_zup : bool, optional
908- Whether to use zup to load glb files. Defaults to False.
931+ This parameter is deprecated, see file_meshes_are_zup.
932+ file_meshes_are_zup : bool, optional
933+ Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
934+ as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
935+ where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
936+ This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
909937 visualization : bool, optional
910938 Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
911939 purposes. Defaults to True. `visualization` and `collision` cannot both be False.
@@ -1003,7 +1031,12 @@ class Drone(FileMorph):
10031031 coacd_options : CoacdOptions, optional
10041032 Options for configuring coacd convex decomposition. Needs to be a `gs.options.CoacdOptions` object.
10051033 parse_glb_with_zup : bool, optional
1006- Whether to use zup to load glb files. Defaults to False.
1034+ This parameter is deprecated, see file_meshes_are_zup.
1035+ file_meshes_are_zup : bool, optional
1036+ Defines if the mesh files are expressed in a Z-up or Y-up coordinate system. If set to true, meshes are loaded
1037+ as Z-up and no transforms are applied to the input data. If set to false, all meshes undergo a conversion step
1038+ where the original coordinates are transformed as follows: (X, Y, Z) → (X, -Z, Y).
1039+ This conversion always applies to GLTF/GLB files, as they are defined as Y-up by the standard. Defaults to true.
10071040 visualization : bool, optional
10081041 Whether the entity needs to be visualized. Set it to False if you need a invisible object only for collision
10091042 purposes. Defaults to True. `visualization` and `collision` cannot both be False.
0 commit comments