Skip to content

Commit 19cf0e5

Browse files
ACMLCZHduburcqa
authored andcommitted
[FEATURE] Add New Features for Madrona Batch Rendering (Genesis-Embodied-AI#1563)
Co-authored-by: Alexis DUBURCQ <alexis.duburcq@gmail.com>
1 parent 17cc27f commit 19cf0e5

File tree

12 files changed

+577
-188
lines changed

12 files changed

+577
-188
lines changed

examples/rigid/single_franka_batch_render.py

Lines changed: 37 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -13,16 +13,20 @@ def main():
1313
parser.add_argument("-b", "--n_envs", type=int, default=3)
1414
parser.add_argument("-s", "--n_steps", type=int, default=2)
1515
parser.add_argument("-r", "--render_all_cameras", action="store_true", default=False)
16-
parser.add_argument("-o", "--output_dir", type=str, default="img_output/test")
16+
parser.add_argument("-o", "--output_dir", type=str, default="data/test")
1717
parser.add_argument("-u", "--use_rasterizer", action="store_true", default=False)
1818
parser.add_argument("-d", "--debug", action="store_true", default=False)
19+
parser.add_argument("-l", "--seg_level", type=str, default="link")
1920
args = parser.parse_args()
2021

2122
########################## init ##########################
2223
gs.init(backend=gs.cpu if args.cpu else gs.gpu)
2324

2425
########################## create a scene ##########################
2526
scene = gs.Scene(
27+
vis_options=gs.options.VisOptions(
28+
segmentation_level=args.seg_level,
29+
),
2630
renderer=gs.options.renderers.BatchRenderer(
2731
use_rasterizer=args.use_rasterizer,
2832
),
@@ -61,21 +65,31 @@ def main():
6165
fov=45,
6266
GUI=args.vis,
6367
)
68+
cam_2 = scene.add_camera(
69+
res=(512, 512),
70+
pos=(0.0, 0.1, 5.0),
71+
lookat=(0.0, 0.0, 0.0),
72+
fov=45,
73+
GUI=args.vis,
74+
)
75+
6476
scene.add_light(
65-
pos=[0.0, 0.0, 1.5],
66-
dir=[1.0, 1.0, -2.0],
67-
directional=1,
68-
castshadow=1,
77+
pos=(0.0, 0.0, 1.5),
78+
dir=(1.0, 1.0, -2.0),
79+
color=(1.0, 0.0, 0.0),
80+
directional=True,
81+
castshadow=True,
6982
cutoff=45.0,
7083
intensity=0.5,
7184
)
7285
scene.add_light(
73-
pos=[4, -4, 4],
74-
dir=[-1, 1, -1],
75-
directional=0,
76-
castshadow=1,
77-
cutoff=45.0,
78-
intensity=0.5,
86+
pos=(4, -4, 4),
87+
dir=(0, 0, -1),
88+
directional=False,
89+
castshadow=True,
90+
cutoff=80.0,
91+
intensity=1.0,
92+
attenuation=0.1,
7993
)
8094

8195
########################## build ##########################
@@ -91,11 +105,19 @@ def main():
91105
if args.debug:
92106
debug_cam.render()
93107
if args.render_all_cameras:
94-
rgba, depth, _, _ = scene.render_all_cameras(rgb=True, depth=True)
95-
exporter.export_frame_all_cameras(i, rgb=rgba, depth=depth)
108+
color, depth, seg, normal = scene.render_all_cameras(
109+
rgb=True, depth=i % 2 == 1, segmentation=i % 2 == 1, normal=True
110+
)
111+
exporter.export_frame_all_cameras(i, rgb=color, depth=depth, segmentation=seg, normal=normal)
96112
else:
97-
rgba, depth, _, _ = cam_1.render(rgb=True, depth=True)
98-
exporter.export_frame_single_camera(i, cam_1.idx, rgb=rgba, depth=depth)
113+
color, depth, seg, normal = cam_1.render(
114+
rgb=False,
115+
depth=True,
116+
segmentation=True,
117+
colorize_seg=True,
118+
normal=False,
119+
)
120+
exporter.export_frame_single_camera(i, cam_1.idx, rgb=seg, depth=depth, segmentation=None, normal=normal)
99121
if args.debug:
100122
debug_cam.stop_recording("debug_cam.mp4")
101123

genesis/engine/scene.py

Lines changed: 107 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -451,77 +451,94 @@ def link_entities(
451451
parent_link._child_idxs.append(child_link.idx)
452452

453453
@gs.assert_unbuilt
454-
def add_light(
454+
def add_mesh_light(
455455
self,
456-
*,
457456
morph: Morph | None = None,
458457
color: ArrayLike | None = (1.0, 1.0, 1.0, 1.0),
459458
intensity: float = 20.0,
460459
revert_dir: bool | None = False,
461460
double_sided: bool | None = False,
462-
beam_angle: float | None = 180.0,
463-
pos: ArrayLike | None = None,
464-
dir: ArrayLike | None = None,
465-
directional: bool | None = None,
466-
castshadow: bool | None = None,
467-
cutoff: float | None = None,
461+
cutoff: float | None = 180.0,
468462
):
469463
"""
470-
Add a light to the scene.
471-
472-
Warning
473-
-------
474-
The signature of this method is different depending on the renderer being used, i.e.:
475-
- RayTracer: 'add_light(self, morph, color, intensity, revert_dir, double_sided, beam_angle)'
476-
- BatchRender: 'add_ligth(self, pos, dir, intensity, directional, castshadow, cutoff)'
477-
- Rasterizer: **Unsupported**
464+
Add a mesh light to the scene. Only supported by RayTracer.
478465
479466
Parameters
480467
----------
481468
morph : gs.morphs.Morph
482-
The morph of the light. Must be an instance of `gs.morphs.Primitive` or `gs.morphs.Mesh`. Only supported by
483-
RayTracer.
469+
The morph of the light. Must be an instance of `gs.morphs.Primitive` or `gs.morphs.Mesh`.
484470
color : tuple of float, shape (3,)
485-
The color of the light, specified as (r, g, b). Only supported by RayTracer.
471+
The color of the light, specified as (r, g, b).
486472
intensity : float
487473
The intensity of the light.
488474
revert_dir : bool
489475
Whether to revert the direction of the light. If True, the light will be emitted towards the mesh's inside.
490-
Only supported by RayTracer.
491476
double_sided : bool
492-
Whether to emit light from both sides of surface. Only supported by RayTracer.
493-
beam_angle : float
494-
The beam angle of the light. Only supported by RayTracer.
477+
Whether to emit light from both sides of surface.
478+
cutoff : float
479+
The cutoff angle of the light in degrees. Range: [0.0, 180.0].
480+
"""
481+
if not isinstance(self.renderer_options, gs.renderers.RayTracer):
482+
if isinstance(self.renderer_options, gs.renderers.BatchRenderer):
483+
gs.raise_exception(
484+
"This method is only supported by RayTracer. Please use 'add_light' when using BatchRenderer."
485+
)
486+
else:
487+
gs.raise_exception(
488+
"This method is only supported by RayTracer. Impossible to add light when using Rasterizer."
489+
)
490+
491+
if not isinstance(morph, (gs.morphs.Primitive, gs.morphs.Mesh)):
492+
gs.raise_exception("Light morph only supports `gs.morphs.Primitive` or `gs.morphs.Mesh`.")
493+
mesh = gs.Mesh.from_morph_surface(morph, gs.surfaces.Plastic(smooth=False))
494+
self._visualizer.add_mesh_light(mesh, color, intensity, morph.pos, morph.quat, revert_dir, double_sided, cutoff)
495+
496+
@gs.assert_unbuilt
497+
def add_light(
498+
self,
499+
pos: ArrayLike,
500+
dir: ArrayLike,
501+
color: ArrayLike = (1.0, 1.0, 1.0),
502+
intensity: float = 1.0,
503+
directional: bool = False,
504+
castshadow: bool = True,
505+
cutoff: float = 45.0,
506+
attenuation: float = 0.0,
507+
):
508+
"""
509+
Add a light to the scene for batch renderer.
510+
511+
Parameters
512+
----------
495513
pos : tuple of float, shape (3,)
496-
The position of the light, specified as (x, y, z). Only supported by BatchRenderer.
514+
The position of the light, specified as (x, y, z).
497515
dir : tuple of float, shape (3,)
498-
The direction of the light, specified as (x, y, z). Only supported by BatchRenderer.
516+
The direction of the light, specified as (x, y, z).
517+
color : tuple of float, shape (3,)
518+
The color of the light, specified as (r, g, b).
499519
intensity : float
500-
The intensity of the light. Only supported by BatchRenderer.
520+
The intensity of the light.
501521
directional : bool
502-
Whether the light is directional. Only supported by BatchRenderer.
522+
Whether the light is directional.
503523
castshadow : bool
504-
Whether the light casts shadows. Only supported by BatchRenderer.
524+
Whether the light casts shadows.
505525
cutoff : float
506-
The cutoff angle of the light in degrees. Only supported by BatchRenderer.
526+
The cutoff angle of the light in degrees. Range: (0.0, 90.0).
527+
attenuation : float
528+
The attenuation factor of the light.
529+
Light intensity will attenuate by distance with (1 / (1 + attenuation * distance ^ 2))
507530
"""
508-
if self._visualizer.batch_renderer is not None:
509-
if any(map(lambda e: e is None, (pos, dir, intensity, directional, castshadow, cutoff))):
510-
gs.raise_exception("Input arguments do not complain with expected signature when using 'BatchRenderer'")
511-
512-
self.visualizer.add_light(pos, dir, intensity, directional, castshadow, cutoff)
513-
elif self.visualizer.raytracer is not None:
514-
if any(map(lambda e: e is None, (morph, color, intensity, revert_dir, double_sided, beam_angle))):
515-
gs.raise_exception("Input arguments do not complain with expected signature when using 'RayTracer'")
516-
if not isinstance(morph, (gs.morphs.Primitive, gs.morphs.Mesh)):
517-
gs.raise_exception("Light morph only supports `gs.morphs.Primitive` or `gs.morphs.Mesh`.")
518-
519-
mesh = gs.Mesh.from_morph_surface(morph, gs.surfaces.Plastic(smooth=False))
520-
self.visualizer.raytracer.add_mesh_light(
521-
mesh, color, intensity, morph.pos, morph.quat, revert_dir, double_sided, beam_angle
522-
)
523-
else:
524-
gs.raise_exception("Adding lights is only supported by 'RayTracer' and 'BatchRenderer'.")
531+
if not isinstance(self.renderer_options, gs.renderers.BatchRenderer):
532+
if isinstance(self.renderer_options, gs.renderers.BatchRenderer):
533+
gs.raise_exception(
534+
"This method is only supported by BatchRenderer. Please use 'add_mesh_light' when using RayTracer."
535+
)
536+
else:
537+
gs.raise_exception(
538+
"This method is only supported by BatchRenderer. Impossible to add light when using Rasterizer."
539+
)
540+
541+
self.visualizer.add_light(pos, dir, color, intensity, directional, castshadow, cutoff, attenuation)
525542

526543
@gs.assert_unbuilt
527544
def add_sensor(self, sensor_options: "SensorOptions"):
@@ -541,6 +558,8 @@ def add_camera(
541558
GUI=False,
542559
spp=256,
543560
denoise=None,
561+
near=0.05,
562+
far=100.0,
544563
env_idx=None,
545564
debug=False,
546565
):
@@ -581,6 +600,12 @@ def add_camera(
581600
Whether to denoise the camera's rendered image. Only available when using the RayTracer renderer. Defaults
582601
to True on Linux, otherwise False. If OptiX denoiser is not available in your platform, consider enabling
583602
the OIDN denoiser option when building the RayTracer.
603+
near : float
604+
Distance from camera center to near plane in meters.
605+
Only available when using rasterizer in Rasterizer and BatchRender renderer. Defaults to 0.05.
606+
far : float
607+
Distance from camera center to far plane in meters.
608+
Only available when using rasterizer in Rasterizer and BatchRender renderer. Defaults to 100.0.
584609
env_idx : int, optional
585610
The specific environment index to bind to the camera. This option must be specified if and only if a
586611
non-batched renderer is being used. If provided, only this environment will be taken into account when
@@ -602,7 +627,7 @@ def add_camera(
602627
if denoise is None:
603628
denoise = sys.platform != "darwin"
604629
return self._visualizer.add_camera(
605-
res, pos, lookat, up, model, fov, aperture, focus_dist, GUI, spp, denoise, env_idx, debug
630+
res, pos, lookat, up, model, fov, aperture, focus_dist, GUI, spp, denoise, near, far, env_idx, debug
606631
)
607632

608633
@gs.assert_unbuilt
@@ -1120,7 +1145,16 @@ def draw_debug_path(self, qposs, entity, link_idx=-1, density=0.3, frame_scaling
11201145
)
11211146

11221147
@gs.assert_built
1123-
def render_all_cameras(self, rgb=True, depth=False, normal=False, segmentation=False, force_render=False):
1148+
def render_all_cameras(
1149+
self,
1150+
rgb=True,
1151+
depth=False,
1152+
segmentation=False,
1153+
colorize_seg=False,
1154+
normal=False,
1155+
antialiasing=False,
1156+
force_render=False,
1157+
):
11241158
"""
11251159
Render the scene for all cameras using the batch renderer.
11261160
@@ -1130,10 +1164,12 @@ def render_all_cameras(self, rgb=True, depth=False, normal=False, segmentation=F
11301164
Whether to render the rgb image.
11311165
depth : bool, optional
11321166
Whether to render the depth image.
1133-
normal : bool, optional
1134-
Whether to render the normal image.
11351167
segmentation : bool, optional
11361168
Whether to render the segmentation image.
1169+
normal : bool, optional
1170+
Whether to render the normal image.
1171+
antialiasing : bool, optional
1172+
Whether to apply anti-aliasing.
11371173
force_render : bool, optional
11381174
Whether to force render the scene.
11391175
@@ -1145,7 +1181,12 @@ def render_all_cameras(self, rgb=True, depth=False, normal=False, segmentation=F
11451181
if self._visualizer.batch_renderer is None:
11461182
gs.raise_exception("Method only supported by 'BatchRenderer'")
11471183

1148-
return self._visualizer.batch_renderer.render(rgb, depth, normal, segmentation, force_render)
1184+
rgb_out, depth_out, seg_out, normal_out = self._visualizer.batch_renderer.render(
1185+
rgb, depth, segmentation, normal, antialiasing, force_render
1186+
)
1187+
if segmentation and colorize_seg:
1188+
seg_out = tuple(self._visualizer.batch_renderer.colorize_seg_idxc_arr(seg) for seg in seg_out)
1189+
return rgb_out, depth_out, seg_out, normal_out
11491190

11501191
@gs.assert_built
11511192
def clear_debug_object(self, object):
@@ -1396,3 +1437,18 @@ def fem_solver(self):
13961437
def pbd_solver(self):
13971438
"""The scene's `pbd_solver`, managing all the `PBDEntity` in the scene."""
13981439
return self._sim.pbd_solver
1440+
1441+
@property
1442+
def segmentation_idx_dict(self):
1443+
"""
1444+
Returns a dictionary mapping segmentation indices to scene entities.
1445+
1446+
In the segmentation map:
1447+
- Index 0 corresponds to the background (-1).
1448+
- Indices > 0 correspond to scene elements, which may be represented as:
1449+
- `entity_id`
1450+
- `(entity_id, link_id)`
1451+
- `(entity_id, link_id, geom_id)`
1452+
depending on the material type and the configured segmentation level.
1453+
"""
1454+
return self._visualizer.segmentation_idx_dict

genesis/options/surfaces.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -67,8 +67,8 @@ class Surface(Options):
6767
double_sided : bool | None, optional
6868
Whether to render both sides of the surface. Useful for non-watertight 2D objects. Defaults to True for Cloth
6969
material and False for others.
70-
beam_angle : float
71-
The beam angle of emission. Defaults to 180.0.
70+
cutoff : float
71+
The cutoff angle of emission. Defaults to 180.0.
7272
normal_diff_clamp : float, optional
7373
Controls the threshold for computing surface normals by interpolating vertex normals.
7474
recon_backend : str, optional
@@ -99,8 +99,8 @@ class Surface(Options):
9999
vis_mode: Optional[str] = None
100100
smooth: bool = True
101101
double_sided: Optional[bool] = None
102-
beam_angle: float = 180
103-
normal_diff_clamp: float = 180
102+
cutoff: float = 180.0
103+
normal_diff_clamp: float = 180.0
104104
recon_backend: str = "splashsurf"
105105
generate_foam: bool = False
106106
foam_options: Optional[FoamOptions] = None

genesis/utils/image_exporter.py

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -194,15 +194,12 @@ def export_frame_single_camera(
194194
imgs_data = np.asarray(imgs_data)
195195

196196
# Make sure that image data has shape `(n_env, H, W [, C>1])``
197-
is_single_channel = img_type in (IMAGE_TYPE.DEPTH, IMAGE_TYPE.SEGMENTATION)
198-
if imgs_data.ndim == (2 if is_single_channel else 3):
197+
if imgs_data.ndim < 4:
199198
imgs_data = imgs_data[None]
200-
if imgs_data.ndim == 4 and is_single_channel:
199+
if imgs_data.ndim == 4 and imgs_data.shape[-1] == 1:
201200
imgs_data = imgs_data[..., 0]
202-
if is_single_channel and imgs_data.ndim != 3:
203-
gs.raise_exception("'{imgs_data}' images must be tensors of shape (n_envs, H, W)")
204-
elif not is_single_channel and (imgs_data.ndim != 4 or imgs_data.shape[-1] != 3):
205-
gs.raise_exception("'{imgs_data}' images must be tensors of shape (n_envs, H, W, 3)")
201+
if imgs_data.ndim not in (3, 4):
202+
gs.raise_exception("'{imgs_data}' images must be tensors of shape (n_envs, H, W [, C>1])")
206203

207204
# Convert image data to grayscale array if necessary
208205
if img_type == IMAGE_TYPE.DEPTH:
@@ -214,7 +211,7 @@ def export_frame_single_camera(
214211
imgs_data = imgs_data.astype(np.uint8)
215212

216213
# Flip channel order if necessary
217-
if not is_single_channel:
214+
if imgs_data.ndim == 4:
218215
imgs_data = np.flip(imgs_data, axis=-1)
219216

220217
# Export image array as (compressed) PNG file.

0 commit comments

Comments
 (0)