Scene#

class genesis.engine.scene.Scene(sim_options: SimOptions | None = None, coupler_options: BaseCouplerOptions | None = None, tool_options: ToolOptions | None = None, rigid_options: RigidOptions | None = None, avatar_options: AvatarOptions | None = None, mpm_options: MPMOptions | None = None, sph_options: SPHOptions | None = None, fem_options: FEMOptions | None = None, sf_options: SFOptions | None = None, pbd_options: PBDOptions | None = None, vis_options: VisOptions | None = None, viewer_options: ViewerOptions | None = None, profiling_options: ProfilingOptions | None = None, renderer: RendererOptions | None = None, show_viewer: bool | None = None, show_FPS: bool | None = None)[source]#

A genesis.Scene object wraps all components in a simulation environment, including a simulator (containing multiple physics solvers), entities, and a visualizer (controlling both the viewer and all the cameras). Basically, everything happens inside a scene.

Parameters:
  • sim_options (gs.options.SimOptions) – The options configuring the overarching simulator, which in turn manages all the solvers.

  • coupler_options (gs.options.CouplerOptions) – The options configuring the coupler between different solvers.

  • tool_options (gs.options.ToolOptions) – The options configuring the tool_solver (scene.sim.ToolSolver).

  • rigid_options (gs.options.RigidOptions) – The options configuring the rigid_solver (scene.sim.RigidSolver).

  • avatar_options (gs.options.AvatarOptions) – The options configuring the avatar_solver (scene.sim.AvatarSolver).

  • mpm_options (gs.options.MPMOptions) – The options configuring the mpm_solver (scene.sim.MPMSolver).

  • sph_options (gs.options.SPHOptions) – The options configuring the sph_solver (scene.sim.SPHSolver).

  • fem_options (gs.options.FEMOptions) – The options configuring the fem_solver (scene.sim.FEMSolver).

  • sf_options (gs.options.SFOptions) – The options configuring the sf_solver (scene.sim.SFSolver).

  • pbd_options (gs.options.PBDOptions) – The options configuring the pbd_solver (scene.sim.PBDSolver).

  • vis_options (gs.options.VisOptions) – The options configuring the visualization system (scene.visualizer). Visualizer controls both the interactive viewer and the cameras.

  • viewer_options (gs.options.ViewerOptions) – The options configuring the viewer (scene.visualizer.viewer).

  • renderer (gs.renderers.RendererOptions) – The renderer options used by camera for rendering images. This doesn’t affect the behavior of the interactive viewer.

  • show_viewer (bool) – Whether to show the interactive viewer. Set it to False if you only need headless rendering.

  • show_FPS (bool) – Whether to show the FPS in the terminal.

destroy()[source]#
add_entity(morph: Morph, material: Material | None = None, surface: Surface | None = None, visualize_contact: bool = False, vis_mode: str | None = None)[source]#

Add an entity to the scene.

Parameters:
  • morph (gs.morphs.Morph) – The morph of the entity.

  • material (gs.materials.Material | None, optional) – The material of the entity. If None, use gs.materials.Rigid().

  • surface (gs.surfaces.Surface | None, optional) – The surface of the entity. If None, use gs.surfaces.Default().

  • visualize_contact (bool) – Whether to visualize contact forces applied to this entity as arrows in the viewer and rendered images. Note that this will not be displayed in images rendered by camera using the RayTracer renderer.

  • vis_mode (str | None, optional) – The visualization mode of the entity. This is a handy shortcut for setting surface.vis_mode without explicitly creating a surface object.

Returns:

entity – The created entity.

Return type:

genesis.Entity

links two entities to act as single entity.

Parameters:
  • parent_entity (genesis.Entity) – The entity in the scene that will be a parent of kinematic tree.

  • child_entity (genesis.Entity) – The entity in the scene that will be a child of kinematic tree.

  • parent_link_name (str) – The name of the link in the parent entity to be linked.

  • child_link_name (str) – The name of the link in the child entity to be linked.

add_mesh_light(morph: Morph | None = None, color: _Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] | None = (1.0, 1.0, 1.0, 1.0), intensity: float = 20.0, revert_dir: bool | None = False, double_sided: bool | None = False, cutoff: float | None = 180.0)[source]#

Add a mesh light to the scene. Only supported by RayTracer.

Parameters:
  • morph (gs.morphs.Morph) – The morph of the light. Must be an instance of gs.morphs.Primitive or gs.morphs.Mesh.

  • color (tuple of float, shape (3,)) – The color of the light, specified as (r, g, b).

  • intensity (float) – The intensity of the light.

  • revert_dir (bool) – Whether to revert the direction of the light. If True, the light will be emitted towards the mesh’s inside.

  • double_sided (bool) – Whether to emit light from both sides of surface.

  • cutoff (float) – The cutoff angle of the light in degrees. Range: [0.0, 180.0].

add_light(pos: _Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str], dir: _Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str], color: _Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] = (1.0, 1.0, 1.0), intensity: float = 1.0, directional: bool = False, castshadow: bool = True, cutoff: float = 45.0, attenuation: float = 0.0)[source]#

Add a light to the scene for batch renderer.

Parameters:
  • pos (tuple of float, shape (3,)) – The position of the light, specified as (x, y, z).

  • dir (tuple of float, shape (3,)) – The direction of the light, specified as (x, y, z).

  • color (tuple of float, shape (3,)) – The color of the light, specified as (r, g, b).

  • intensity (float) – The intensity of the light.

  • directional (bool) – Whether the light is directional.

  • castshadow (bool) – Whether the light casts shadows.

  • cutoff (float) – The cutoff angle of the light in degrees. Range: (0.0, 90.0).

  • attenuation (float) – The attenuation factor of the light. Light intensity will attenuate by distance with (1 / (1 + attenuation * distance ^ 2))

add_sensor(sensor_options: SensorOptions)[source]#

Add a sensor to the scene.

Sensors extract information from the scene without modifying the physics simulation.

Parameters:

sensor_options (SensorOptions) – The options for the sensor.

start_recording(data_func: Callable, rec_options: RecorderOptions) Recorder[source]#

Automatically read and process data. See RecorderOptions for more details.

Data from data_func is automatically read and processed using the recorder at the frequency rec_options.hz (or every step if not specified) as the scene is stepped.

Parameters:
  • data_func (Callable) – A function with no arguments that returns the data to be recorded.

  • rec_options (RecorderOptions) – The options for the recording.

Returns:

recorder – The created recorder object.

Return type:

Recorder

add_camera(model='pinhole', res=(320, 320), pos=(0.5, 2.5, 3.5), lookat=(0.5, 0.5, 0.5), up=(0.0, 0.0, 1.0), fov=30, aperture=2.0, focus_dist=None, GUI=False, spp=256, denoise=None, near=0.1, far=20.0, env_idx=None, debug=False)[source]#

Add a camera to the scene.

The camera model can be either ‘pinhole’ or ‘thinlens’. The ‘pinhole’ model is a simple camera model that captures light rays from a single point in space. The ‘thinlens’ model is a more complex camera model that simulates a lens with a finite aperture size, allowing for depth of field effects.

Warning

When ‘pinhole’ is used, the aperture and focal_len parameters are ignored.

Parameters:
  • model (str) – Specifies the camera model. Options are ‘pinhole’ or ‘thinlens’.

  • res (tuple of int, shape (2,)) – The resolution of the camera, specified as a tuple (width, height).

  • pos (tuple of float, shape (3,)) – The position of the camera in the scene, specified as (x, y, z).

  • lookat (tuple of float, shape (3,)) – The point in the scene that the camera is looking at, specified as (x, y, z).

  • up (tuple of float, shape (3,)) – The up vector of the camera, defining its orientation, specified as (x, y, z).

  • fov (float) – The vertical field of view of the camera in degrees.

  • aperture (float) – The aperture size of the camera, controlling depth of field.

  • focus_dist (float | None) – The focus distance of the camera. If None, it will be auto-computed using pos and lookat.

  • GUI (bool) – Whether to display the camera’s rendered image in a separate GUI window.

  • spp (int, optional) – Samples per pixel. Only available when using RayTracer renderer. Defaults to 256.

  • denoise (bool) – Whether to denoise the camera’s rendered image. Only available when using the RayTracer renderer. Defaults to True on Linux, otherwise False. If OptiX denoiser is not available in your platform, consider enabling the OIDN denoiser option when building the RayTracer.

  • near (float) – Distance from camera center to near plane in meters. Only available when using rasterizer in Rasterizer and BatchRender renderer. Defaults to 0.1.

  • far (float) – Distance from camera center to far plane in meters. Only available when using rasterizer in Rasterizer and BatchRender renderer. Defaults to 20.0.

  • env_idx (int, optional) – The specific environment index to bind to the camera. This option must be specified if and only if a non-batched renderer is being used. If provided, only this environment will be taken into account when following a rigid entity via ‘follow_entity’ and when being attached to some rigid link via ‘attach’. Note that this option is unrelated to which environment is being rendering on the scene. Default to None for batched renderers (ie BatchRender), ‘rendered_envs_idx[0]’ otherwise (ie Raytracer or Rasterizer).

  • debug (bool) – Whether to use the debug camera. It enables to create cameras that can used to monitor / debug the simulation without being part of the “sensors”. Their output is rendered by the usual simple Rasterizer systematically, no matter if BatchRender and RayTracer is enabled. This way, it is possible to record the simulation with arbitrary resolution and camera pose, without interfering with what robots can perceive from their environment. Defaults to False.

Returns:

camera – The created camera object.

Return type:

genesis.Camera

add_emitter(material: Material, max_particles=20000, surface: Surface | None = None)[source]#

Add a fluid emitter to the scene.

Parameters:
  • material (gs.materials.Material) – The material of the fluid to be emitted. Must be an instance of gs.materials.MPM.Base, gs.materials.SPH.Base, gs.materials.PBD.Particle or gs.materials.PBD.Liquid.

  • max_particles (int) – The maximum number of particles that can be emitted by the emitter. Particles will be recycled once this limit is reached.

  • surface (gs.surfaces.Surface | None, optional) – The surface of the emitter. If None, use gs.surfaces.Default(color=(0.6, 0.8, 1.0, 1.0)).

Returns:

emitter – The created emitter object.

Return type:

genesis.Emitter

add_force_field(force_field: ForceField)[source]#

Add a force field to the scene.

Parameters:

force_field (gs.force_fields.ForceField) – The force field to add to the scene.

Returns:

force_field – The added force field.

Return type:

gs.force_fields.ForceField

build(n_envs=0, env_spacing=(0.0, 0.0), n_envs_per_row: int | None = None, center_envs_at_origin=True, compile_kernels=None)[source]#

Builds the scene once all entities have been added. This operation is required before running the simulation.

Parameters:
  • n_envs (int) – Number of parallel environments to create. If n_envs is 0, the scene will not have a batching dimension. When greater than 0, the first dimension of all the input and returned states will be the batch dimension.

  • env_spacing (tuple of float, shape (2,)) – The spacing between adjacent environments in the scene. This is for visualization purposes only and does not change simulation-related poses.

  • n_envs_per_row (int) – The number of environments per row for visualization. If None, it will be set to sqrt(n_envs).

  • center_envs_at_origin (bool) – Whether to put the center of all the environments at the origin (for visualization only).

  • compile_kernels (bool, optional) – This parameter is deprecated and will be removed in future release.

reset(state: SimState | None = None, envs_idx=None)[source]#

Resets the scene to its initial state.

Parameters:
  • state (SimState | None) – The state to reset the scene to. If None, the scene will be reset to its initial state. If this is given, the scene’s registerered initial state will be updated to this state.

  • envs_idx (None | array_like, optional) – The indices of the environments. If None, all environments will be considered. Defaults to None.

get_state()[source]#

Returns the current state of the scene.

Returns:

state – The state of the scene at the current time step.

Return type:

genesis.SimState

step(update_visualizer=True, refresh_visualizer=True)[source]#

Runs a simulation step forward in time.

stop_recording()[source]#
draw_debug_line(start, end, radius=0.002, color=(1.0, 0.0, 0.0, 0.5))[source]#

Draws a line in the scene for visualization.

Parameters:
  • start (array_like, shape (3,)) – The starting point of the line.

  • end (array_like, shape (3,)) – The ending point of the line.

  • radius (float, optional) – The radius of the line (represented as a cylinder)

  • color (array_like, shape (4,), optional) – The color of the line in RGBA format.

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_arrow(pos, vec=(0, 0, 1), radius=0.01, color=(1.0, 0.0, 0.0, 0.5))[source]#

Draws an arrow in the scene for visualization.

Parameters:
  • pos (array_like, shape (3,)) – The starting position of the arrow.

  • vec (array_like, shape (3,), optional) – The vector of the arrow.

  • radius (float, optional) – The radius of the arrow body (represented as a cylinder).

  • color (array_like, shape (4,), optional) – The color of the arrow in RGBA format.

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_frame(T, axis_length=1.0, origin_size=0.015, axis_radius=0.01)[source]#

Draws a 3-axis coordinate frame in the scene for visualization.

Parameters:
  • T (array_like, shape (4, 4)) – The transformation matrix of the frame.

  • axis_length (float, optional) – The length of the axes.

  • origin_size (float, optional) – The size of the origin point (represented as a sphere).

  • axis_radius (float, optional) – The radius of the axes (represented as cylinders).

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_frames(Ts, axis_length=1.0, origin_size=0.015, axis_radius=0.01)[source]#

Draws 3-axis coordinate frames in the scene for visualization.

Parameters:
  • Ts (array_like, shape (n, 4, 4)) – The transformation matrices of frames.

  • axis_length (float, optional) – The length of the axes.

  • origin_size (float, optional) – The size of the origin point (represented as a sphere).

  • axis_radius (float, optional) – The radius of the axes (represented as cylinders).

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_mesh(mesh, pos=array([0., 0., 0.]), T=None)[source]#

Draws a mesh in the scene for visualization.

Parameters:
  • mesh (trimesh.Trimesh) – The mesh to be drawn.

  • pos (array_like, shape (3,), optional) – The position of the mesh in the scene.

  • T (array_like, shape (4, 4) | None, optional) – The transformation matrix of the mesh. If None, the mesh will be drawn at the position specified by pos. Otherwise, T has a higher priority than pos.

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_sphere(pos, radius=0.01, color=(1.0, 0.0, 0.0, 0.5))[source]#

Draws a sphere in the scene for visualization.

Parameters:
  • pos (array_like, shape (3,)) – The center position of the sphere.

  • radius (float, optional) – radius of the sphere.

  • color (array_like, shape (4,), optional) – The color of the sphere in RGBA format.

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_spheres(poss, radius=0.01, color=(1.0, 0.0, 0.0, 0.5))[source]#

Draws multiple spheres in the scene for visualization.

Parameters:
  • poss (array_like, shape (N, 3)) – The positions of the spheres.

  • radius (float, optional) – The radius of the spheres.

  • color (array_like, shape (4,), optional) – The color of the spheres in RGBA format.

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_box(bounds, color=(1.0, 0.0, 0.0, 1.0), wireframe=True, wireframe_radius=0.0015)[source]#

Draws a box in the scene for visualization.

Parameters:
  • bounds (array_like, shape (2, 3)) – The bounds of the box, specified as [[min_x, min_y, min_z], [max_x, max_y, max_z]].

  • color (array_like, shape (4,), optional) – The color of the box in RGBA format.

  • wireframe (bool, optional) – Whether to draw the box as a wireframe.

  • wireframe_radius (float, optional) – The radius of the wireframe lines.

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_points(poss, colors=(1.0, 0.0, 0.0, 0.5))[source]#

Draws points in the scene for visualization.

Parameters:
  • poss (array_like, shape (N, 3)) – The positions of the points.

  • colors (array_like, shape (4,), optional) – The color of the points in RGBA format.

Returns:

node – The created debug object.

Return type:

genesis.ext.pyrender.mesh.Mesh

draw_debug_path(qposs, entity, link_idx=-1, density=0.3, frame_scaling=1.0)[source]#

Draws a planned joint trajectory in the scene for visualization.

Parameters:
  • qposs (array_like, shape (N, M)) – The joint positions of the planned points. N is the number of configurations (i.e., trajectory points). M is the number of degrees of freedom for the entity (i.e., joint dimensions).

  • entity (gs.engine.entities.RigidEntity) – The rigid entity whose forward kinematics are used to compute the trajectory path.

  • link_idx (int, optional) – The link id of the rigid entity to visualize. Defeault is -1.

  • density (float, optional) – Controls the sampling density of the trajectory points to visualize. Default is 0.3.

  • frame_scaling (float, optional) – Scaling factor for the visualization frames’ size. Affects the length and thickness of the debug frames. Default is 1.0.

Returns:

node – The created debug object representing the visualized trajectory.

Return type:

genesis.ext.pyrender.mesh.Mesh

Notes

The function uses forward kinematics (FK) to convert joint positions to Cartesian space and render debug frames. The density parameter reduces FK computational load by sampling fewer points, with 1.0 representing the whole trajectory.

render_all_cameras(rgb=True, depth=False, segmentation=False, colorize_seg=False, normal=False, antialiasing=False, force_render=False)[source]#

Render the scene for all cameras using the batch renderer.

Parameters:
  • rgb (bool, optional) – Whether to render the rgb image.

  • depth (bool, optional) – Whether to render the depth image.

  • segmentation (bool, optional) – Whether to render the segmentation image.

  • normal (bool, optional) – Whether to render the normal image.

  • antialiasing (bool, optional) – Whether to apply anti-aliasing.

  • force_render (bool, optional) – Whether to force render the scene.

  • Returns – A tuple of tensors of shape (n_envs, H, W, 3) if rgb is not None, otherwise a list of tensors of shape (n_envs, H, W) if depth is not None. If n_envs == 0, the first dimension of the tensor is squeezed.

clear_debug_object(obj)[source]#

Clears all the debug objects in the scene.

clear_debug_objects()[source]#

Clears all the debug objects in the scene.

dump_ckpt_to_numpy() dict[str, ndarray][source]#

Collect every Taichi field in the scene and its active solvers and return them as a flat {key: ndarray} dictionary.

Returns:

Mapping "Class.attr[.member]" -> array with raw field data.

Return type:

dict[str, np.ndarray]

save_checkpoint(path: str | PathLike) None[source]#

Pickle the full physics state to one file.

Parameters:

path (str | os.PathLike) – Destination filename.

load_checkpoint(path: str | PathLike) None[source]#

Restore a file produced by save_checkpoint().

Parameters:

path (str | os.PathLike) – Path to the checkpoint pickle.

property uid#

The unique ID of the scene.

property dt#

The time duration for each simulation step.

property t#

The current simulation time step.

property substeps#

The number of substeps per simulation step.

property requires_grad#

Whether the scene is in differentiable mode.

property is_built: bool#

Whether the scene has been built.

property show_FPS#

Whether to print the frames per second (FPS) in the terminal.

property gravity#

The gravity in the scene.

property viewer#

The viewer object for the scene.

property visualizer#

The visualizer object for the scene.

property sim#

The scene’s top-level simulator.

property cur_t#

The current simulation time.

property solvers#

All the solvers managed by the scene’s simulator.

property active_solvers#

All the active solvers managed by the scene’s simulator.

property entities: list[Entity]#

All the entities in the scene.

property emitters#

All the emitters in the scene.

property tool_solver#

The scene’s tool_solver, managing all the ToolEntity in the scene.

property rigid_solver#

The scene’s rigid_solver, managing all the RigidEntity in the scene.

property avatar_solver#

The scene’s avatar_solver, managing all the AvatarEntity in the scene.

property mpm_solver#

The scene’s mpm_solver, managing all the MPMEntity in the scene.

property sph_solver#

The scene’s sph_solver, managing all the SPHEntity in the scene.

property fem_solver#

The scene’s fem_solver, managing all the FEMEntity in the scene.

property pbd_solver#

The scene’s pbd_solver, managing all the PBDEntity in the scene.

property segmentation_idx_dict#

Returns a dictionary mapping segmentation indices to scene entities.

In the segmentation map: - Index 0 corresponds to the background (-1). - Indices > 0 correspond to scene elements, which may be represented as:

  • entity_id

  • (entity_id, link_id)

  • (entity_id, link_id, geom_id)

depending on the material type and the configured segmentation level.