@@ -371,12 +371,9 @@ def test_obj_morphes_yup(show_viewer):
371371
372372
373373@pytest .mark .required
374- @pytest .mark .parametrize ("scale" , [(2.0 , 3.0 , 5.0 ), (2.0 , 2.0 , 2.0 )])
375- @pytest .mark .parametrize (
376- "mesh_file, file_meshes_are_zup" ,
377- [("meshes/camera/camera.glb" , False ), ("meshes/axis.obj" , True )],
378- )
379- def test_morph_scale (scale , mesh_file , file_meshes_are_zup , show_viewer , tmp_path ):
374+ @pytest .mark .parametrize ("scale" , [(0.5 , 2.0 , 8.0 ), (2.0 , 2.0 , 2.0 )])
375+ @pytest .mark .parametrize ("mesh_file" , ["meshes/camera/camera.glb" , "meshes/axis.obj" ])
376+ def test_morph_scale (scale , mesh_file , show_viewer , tmp_path ):
380377 urdf_path = tmp_path / "model.urdf"
381378 urdf_path .write_text (
382379 f"""<robot name="cannon">
@@ -393,43 +390,69 @@ def test_morph_scale(scale, mesh_file, file_meshes_are_zup, show_viewer, tmp_pat
393390 obj_orig = scene .add_entity (
394391 morph = gs .morphs .Mesh (
395392 file = mesh_file ,
393+ file_meshes_are_zup = False ,
396394 pos = (0 , 0 , 1.0 ),
397- scale = ( 1.0 , 1.0 , 1.0 ) ,
395+ scale = 1.0 ,
398396 convexify = False ,
399397 fixed = True ,
400398 ),
399+ surface = gs .surfaces .Default (
400+ color = (1.0 , 0.0 , 0.0 , 1.0 ),
401+ ),
401402 )
402- mesh_orig = obj_orig .vgeoms [0 ].vmesh .trimesh
403+ for vgeom in obj_orig .vgeoms :
404+ mesh_orig = vgeom .vmesh .trimesh
405+ mesh_orig .apply_transform (mu .Y_UP_TRANSFORM )
406+ mesh_orig .apply_scale (scale )
407+
403408 obj_scaled = scene .add_entity (
404409 morph = gs .morphs .Mesh (
405410 file = mesh_file ,
411+ file_meshes_are_zup = True ,
406412 pos = (0 , 0 , 1.0 ),
407413 scale = scale ,
408414 convexify = False ,
409415 fixed = True ,
410416 ),
417+ surface = gs .surfaces .Default (
418+ color = (0.0 , 1.0 , 0.0 , 1.0 ),
419+ ),
411420 )
412- mesh_scaled = obj_scaled .vgeoms [ 0 ]. vmesh . trimesh
421+ assert obj_orig . n_vgeoms == obj_scaled .n_vgeoms
413422
414423 is_isotropic = np .unique (scale ).size == 1
415424 with nullcontext () if is_isotropic else pytest .raises (gs .GenesisException ):
416425 robot_scaled = scene .add_entity (
417426 gs .morphs .URDF (
418427 file = urdf_path ,
428+ file_meshes_are_zup = True ,
429+ pos = (0 , 0 , 1.0 ),
430+ scale = scale ,
419431 convexify = False ,
420432 fixed = True ,
421- scale = scale ,
422- file_meshes_are_zup = file_meshes_are_zup ,
433+ ),
434+ surface = gs .surfaces .Default (
435+ color = (0.0 , 0.0 , 1.0 , 1.0 ),
423436 ),
424437 )
425- mesh_robot_scaled = robot_scaled . vgeoms [ 0 ]. vmesh . trimesh
438+ assert robot_scaled . n_vgeoms == obj_scaled . n_vgeoms
426439
427440 if show_viewer :
428441 scene .build ()
429442
430- assert_allclose (mesh_orig .vertices * scale , mesh_scaled .vertices , tol = gs .EPS )
431- if is_isotropic :
432- assert_allclose (mesh_robot_scaled .vertices , mesh_scaled .vertices , tol = gs .EPS )
443+ for i_vg in range (obj_orig .n_vgeoms ):
444+ mesh_orig = obj_orig .vgeoms [i_vg ].vmesh .trimesh .copy ()
445+ mesh_orig .apply_transform (gu .trans_quat_to_T (obj_orig .base_link .pos , obj_orig .base_link .quat ))
446+ mesh_scaled = obj_scaled .vgeoms [i_vg ].vmesh .trimesh .copy ()
447+ mesh_scaled .apply_transform (gu .trans_quat_to_T (obj_scaled .base_link .pos , obj_scaled .base_link .quat ))
448+ assert_allclose (mesh_orig .vertices , mesh_scaled .vertices , tol = gs .EPS )
449+
450+ if is_isotropic :
451+ mesh_robot_scaled = robot_scaled .vgeoms [i_vg ].vmesh .trimesh .copy ()
452+ mesh_robot_scaled .apply_transform (
453+ gu .trans_quat_to_T (robot_scaled .base_link .pos , robot_scaled .base_link .quat )
454+ )
455+ assert_allclose (mesh_robot_scaled .vertices , mesh_scaled .vertices , tol = gs .EPS )
433456
434457
435458@pytest .mark .required
0 commit comments