场景 (Scene)#
- class genesis.engine.scene.Scene(*args, **kwargs)[源代码]#
A
genesis.Sceneobject 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.- 参数:
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.Renderer) – The renderer 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.
- add_entity(morph, material=None, surface=None, visualize_contact=False, vis_mode=None)[源代码]#
Add an entity to the scene.
- 参数:
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.
- 返回:
entity – The created entity.
- 返回类型:
genesis.Entity
- add_light(morph, color=(1.0, 1.0, 1.0, 1.0), intensity=20.0, revert_dir=False, double_sided=False, beam_angle=180.0)[源代码]#
Add a light to the scene. Note that lights added this way can be instantiated from morphs (supporting gs.morphs.Primitive or gs.morphs.Mesh), and will only be used by the RayTracer renderer.
- 参数:
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.
beam_angle (float) – The beam angle of the light.
- 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=True)[源代码]#
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. When ‘pinhole’ is used, the aperture and focal_len parameters are ignored.
- 参数:
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. Defaults to 256.
denoise (bool) – Whether to denoise the camera’s rendered image.
- 返回:
camera – The created camera object.
- 返回类型:
genesis.Camera
- add_emitter(material, max_particles=20000, surface=None)[源代码]#
Add a fluid emitter to the scene.
- 参数:
material (gs.materials.Material) – The material of the fluid to be emitted. Must be an instance of gs.materials.MPM.Base or gs.materials.SPH.Base.
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)).
- 返回:
emitter – The created emitter object.
- 返回类型:
genesis.Emitter
- add_force_field(force_field: ForceField)[源代码]#
Add a force field to the scene.
- 参数:
force_field (gs.force_fields.ForceField) – The force field to add to the scene.
- 返回:
force_field – The added force field.
- 返回类型:
gs.force_fields.ForceField
- build(n_envs=0, env_spacing=(0.0, 0.0), n_envs_per_row=None, center_envs_at_origin=True, compile_kernels=True)[源代码]#
Builds the scene once all entities have been added. This operation is required before running the simulation.
- 参数:
n_envs (int) – Number of parallel environments to create. If n_envs is 0, the scene will not have a batching dimension. If n_envs is 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) – Whether to compile the simulation kernels inside build(). If False, the kernels will not be compiled (or loaded if found in the cache) until the first call of scene.step(). This is useful for cases you don’t want to run the actual simulation, but rather just want to visualize the created scene.
- reset(state=None)[源代码]#
Resets the scene to its initial state.
- 参数:
state (dict | 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.
- get_state()[源代码]#
Returns the current state of the scene.
- 返回:
state – The state of the scene at the current time step.
- 返回类型:
genesis.SimState
- draw_debug_line(start, end, radius=0.002, color=(1.0, 0.0, 0.0, 0.5))[源代码]#
Draws a line in the scene for visualization.
- 参数:
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.
- draw_debug_arrow(pos, vec=(0, 0, 1), radius=0.01, color=(1.0, 0.0, 0.0, 0.5))[源代码]#
Draws an arrow in the scene for visualization.
- 参数:
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.
- draw_debug_frame(T, axis_length=1.0, origin_size=0.015, axis_radius=0.01)[源代码]#
Draws a 3-axis coordinate frame in the scene for visualization.
- 参数:
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).
- draw_debug_mesh(mesh, pos=array([0., 0., 0.]), T=None)[源代码]#
Draws a mesh in the scene for visualization.
- 参数:
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.
- draw_debug_sphere(pos, radius=0.01, color=(1.0, 0.0, 0.0, 0.5))[源代码]#
Draws a sphere in the scene for visualization.
- 参数:
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.
- draw_debug_spheres(poss, radius=0.01, color=(1.0, 0.0, 0.0, 0.5))[源代码]#
Draws multiple spheres in the scene for visualization.
- 参数:
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.
- draw_debug_box(bounds, color=(1.0, 0.0, 0.0, 1.0), wireframe=True, wireframe_radius=0.0015)[源代码]#
Draws a box in the scene for visualization.
- 参数:
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.
- draw_debug_points(poss, colors=(1.0, 0.0, 0.0, 0.5))[源代码]#
Draws points in the scene for visualization.
- 参数:
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.
- 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#
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#
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.