[Question] Blurry render when importing sub-prim USD with SDF collision in Isaac Lab (works fine in Isaac Sim)
Question
Blurry render when importing sub-prim USD with SDF collision in Isaac Lab (works fine in Isaac Sim)
Isaac Sim Version
[ ] 5.0.0
Isaac Lab Version
[ ] 2.2.1
Operating System
[ ] Ubuntu 22.04
GPU Information
- Model: NVIDIA GeForce RTX 5090
- Driver Version: Driver 580.95.05
Topic Description
Blurry render when importing sub-prim USD with SDF collision in Isaac Lab (works fine in Isaac Sim)
Detailed Description
Summary
When I import objects (as sub-prims from another USD asset) into Isaac Lab and apply SDF collisions, the objects appear visibly blurred/soft in both the simulation GUI and the recorded camera images.
The same USD + SDF setup in Isaac Sim renders crisp, without blur.
Environment
- OS: Ubuntu 22.04
- GPU: NVIDIA GeForce RTX 5090, Driver 580.95.05
- Isaac Sim: 2.2.1
What changed
- In Isaac Sim, importing these sub-prims and applying SDF works with no blur (video attached: “Sim_OK.mp4”).
- In Isaac Lab, the same USD source imported similarly (and with SDF) appears blurred (video attached: “Lab_Blur.mp4”).
Minimal code (Isaac Lab)
for i in range(args.num_envs):
env = f"/World/envs/env_{i}"
spawn_subprim_ref(stage, f"{env}/ObjectCylinder", asset02, cylinder_sub,
scale=[0.01, 0.01, 0.04], translate=(0.018, 0.018, 0.08), mass=mass)
spawn_subprim_ref(stage, f"{env}/ObjectCube", asset02, cube_sub,
scale=[0.03, 0.01, 0.01], translate=(0.03, 0.01, 0.01), mass=mass)
spawn_subprim_ref(stage, f"{env}/ObjectFrame", asset02, frame_sub,
scale=[0.01, 0.01, 0.01], translate=(0.02, 0.02, 0.02), mass=mass)
def spawn_subprim_ref(stage, root_prim_path: str, usd_path: str, sub_prim: str,
*, scale=(0.01,0.01,0.01), translate=(0.6,0.0,0.05),
mass=0.05, sdf_resolution=256):
root = stage.DefinePrim(root_prim_path, "Xform")
root.SetInstanceable(False)
UsdPhysics.RigidBodyAPI.Apply(root)
UsdPhysics.MassAPI.Apply(root).CreateMassAttr(0.5)
PhysxSchema.PhysxRigidBodyAPI.Apply(root).CreateDisableGravityAttr(False)
root.GetReferences().AddReference(Sdf.Reference(assetPath=usd_path, primPath=sub_prim))
x = UsdGeom.XformCommonAPI(root)
x.SetScale(tuple(map(float, scale)))
x.SetTranslate(tuple(map(float, translate)))
# Apply SDF broadly to children under this root
for p in Usd.PrimRange(root):
UsdPhysics.CollisionAPI.Apply(p)
mc = UsdPhysics.MeshCollisionAPI.Apply(p)
mc.CreateApproximationAttr().Set(PhysxSchema.Tokens.sdf)
sdf = PhysxSchema.PhysxSDFMeshCollisionAPI.Apply(p)
sdf.CreateSdfResolutionAttr().Set(int(sdf_resolution))
sdf.CreateSdfSubgridResolutionAttr().Set(int(6))
sdf.CreateSdfNarrowBandThicknessAttr().Set(float(0.01))
Minimal code (Isaac Sim, works fine)
def spawn_target(stage):
USD = "/.../scene/Asset_01.usd"
targets = {
"/World/CubeBottom": ("/root/Cube", (0.6, 0, 0.07), (0.01, 0.01, 0.03)),
"/World/CubeTop": ("/root/Cube_001", (0.8, 0, 0.01), (0.01, 0.01, 0.01)),
}
for mount, (subpath, translate, scale) in targets.items():
prim = stage.DefinePrim(mount)
prim.GetReferences().AddReference(Sdf.Reference(assetPath=USD, primPath=subpath))
x = UsdGeom.XformCommonAPI(prim)
x.SetTranslate(translate)
x.SetScale(scale)
for mount in ("/World/CubeTop", "/World/CubeBottom"):
root = stage.GetPrimAtPath(mount)
root.SetInstanceable(False)
UsdPhysics.RigidBodyAPI.Apply(root)
UsdPhysics.MassAPI.Apply(root).CreateMassAttr(0.5)
PhysxSchema.PhysxRigidBodyAPI.Apply(root).CreateDisableGravityAttr(False)
for p in Usd.PrimRange(root):
if p.IsA(UsdGeom.Mesh):
apply_sdf(p, resolution=256, subgrid=6, narrow_band=0.01)
elif p.IsA(UsdGeom.Gprim):
UsdPhysics.CollisionAPI.Apply(p)
def apply_sdf(mesh_prim, *, resolution=256, subgrid=6, narrow_band=0.01, tri_reduce=None):
UsdPhysics.CollisionAPI.Apply(mesh_prim)
mc = UsdPhysics.MeshCollisionAPI.Apply(mesh_prim)
mc.CreateApproximationAttr().Set(PhysxSchema.Tokens.sdf)
sdf = PhysxSchema.PhysxSDFMeshCollisionAPI.Apply(mesh_prim)
sdf.CreateSdfResolutionAttr().Set(int(resolution))
sdf.CreateSdfSubgridResolutionAttr().Set(int(subgrid))
sdf.CreateSdfNarrowBandThicknessAttr().Set(float(narrow_band))
if tri_reduce is not None:
sdf.CreateSdfTriangleCountReductionFactorAttr().Set(float(tri_reduce))
Screenshots or Videos
Blur in Lab
https://github.com/user-attachments/assets/1e864ea5-425c-443e-b600-9db302379d64
OK in sim
https://github.com/user-attachments/assets/c439099d-e4c7-4961-8477-718288cd0685
Additional Information
Based on the code I shared earlier, I do not expect it to cause any blurring on the meshes. If you notice anything incorrect in that code, I would appreciate your feedback. If the problem is not coming from the code, could you please explain what might be causing the behavior described?
Also, following this guidance (https://github.com/isaac-sim/IsaacLab/issues/2188), I tried running with Interactive (Path Tracing) enabled using the setup below:
ap = build_argparser()
args, _ = ap.parse_known_args()
args.enable_cameras = True
args.headless = False
args.renderer = "PathTracing"
from isaaclab.app import AppLauncher
app_launcher = AppLauncher(args)
However, when app.reset() is executed, the system freezes, so I haven’t been able to verify whether this approach improves the blurring issue.
Thank you for posting this. The team will review this.