Skip to content

Commit 8c1d6d4

Browse files
ceasor-maoKashu7100
authored andcommitted
[BUG FIX] Fix point-cloud rendering from Camera depth map. (Genesis-Embodied-AI#1512)
1 parent f9ca3dd commit 8c1d6d4

File tree

1 file changed

+2
-2
lines changed

1 file changed

+2
-2
lines changed

genesis/vis/camera.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -541,10 +541,10 @@ def backproject_depth_to_pointcloud(K: np.ndarray, depth: np.ndarray, pose, worl
541541
point_cloud_h = np.concatenate((pc, np.ones((len(pc), 1), dtype=np.float32)), axis=1)
542542
if world:
543543
point_cloud_world = point_cloud_h @ pose.T
544-
point_cloud_world = point_cloud_world[:, :3].reshape((*depth, 3))
544+
point_cloud_world = point_cloud_world[:, :3].reshape((*depth.shape, 3))
545545
return point_cloud_world, mask
546546
else:
547-
point_cloud = point_cloud_h[:, :3].reshape((*depth, 3))
547+
point_cloud = point_cloud_h[:, :3].reshape((*depth.shape, 3))
548548
return point_cloud, mask
549549

550550
intrinsic_K = opengl_projection_matrix_to_intrinsics(

0 commit comments

Comments
 (0)