Hello World
SAPIEN provides APIs to build physical simulation environments.
In this tutorial, you will learn the following:
Create a simulation engine
Engine
Create a simulation scene
Scene
Setup a renderer to visualize
Run a simulation loop
The full script can be downloaded here hello_world.py
Simulation engine and scene
To simulate with SAPIEN, you need to first create a simulation engine, and then create a simulation scene by the engine.
engine = sapien.Engine() # Create a physical simulation engine
renderer = sapien.SapienRenderer() # Create a renderer
engine.set_renderer(renderer) # Bind the renderer and the engine
scene = engine.create_scene() # Create an instance of simulation world (aka scene)
scene.set_timestep(1 / 100.0) # Set the simulation frequency
Engine
is the physical simulation engine connected to the PhysX
backend. One engine per process is allowed. Creating additional engines without deleting (overwriting the variable, letting it go out of scope) a previous one will result in the same Engine being returned.
Scene
is an instance of the simulation world.
Multiple scenes can be created through create_scene
, and they are independent.
VulkanRenderer
is the rendering engine connected to our Vulkan-based renderer.
the renderer should first be bound with an engine, and then all the scenes created by the engine will be bound with the renderer.
Add rigid bodies
So far, our scene is empty.
In SAPIEN, a simulated rigid body is named an Actor
.
Let’s add two actors, a ground and a box, to the scene.
Actor creation will be elaborated in Create Actors.
scene.add_ground(altitude=0) # Add a ground
actor_builder = scene.create_actor_builder()
actor_builder.add_box_collision(half_size=[0.5, 0.5, 0.5])
actor_builder.add_box_visual(half_size=[0.5, 0.5, 0.5], color=[1., 0., 0.])
box = actor_builder.build(name='box') # Add a box
box.set_pose(sapien.Pose(p=[0, 0, 0.5]))
Viewer
Viewer
creates a window (GUI) to render the simulation world.
It is only available with a connected display (e.g. monitor).
Usage of the GUI will be elaborated in Viewer.
# Add some lights so that you can observe the scene
scene.set_ambient_light([0.5, 0.5, 0.5])
scene.add_directional_light([0, 1, -1], [0.5, 0.5, 0.5])
viewer = Viewer(renderer) # Create a viewer (window)
viewer.set_scene(scene) # Bind the viewer and the scene
# The coordinate frame in Sapien is: x(forward), y(left), z(upward)
# The principle axis of the camera is the x-axis
viewer.set_camera_xyz(x=-4, y=0, z=2)
# The rotation of the free camera is represented as [roll(x), pitch(-y), yaw(-z)]
# The camera now looks at the origin
viewer.set_camera_rpy(r=0, p=-np.arctan2(2, 4), y=0)
viewer.window.set_camera_parameters(near=0.05, far=100, fovy=1)
Note
The GUI is not necessary when you only need physical simulation, e.g. collecting experiences for policy learning.
Simulation loop
After setting up the simulation world, the actual simulation happens in a loop.
For each iteration, the scene simulates for one step and updates the world to the renderer.
The viewer calls render
to update the results on the screen.
while not viewer.closed: # Press key q to quit
scene.step() # Simulate the world
scene.update_render() # Update the world to the renderer
viewer.render()
Full script
1import sapien.core as sapien
2from sapien.utils import Viewer
3import numpy as np
4
5
6def main():
7 engine = sapien.Engine() # Create a physical simulation engine
8 renderer = sapien.SapienRenderer() # Create a renderer
9 engine.set_renderer(renderer) # Bind the renderer and the engine
10
11 scene = engine.create_scene() # Create an instance of simulation world (aka scene)
12 scene.set_timestep(1 / 100.0) # Set the simulation frequency
13
14 # NOTE: How to build actors (rigid bodies) is elaborated in create_actors.py
15 scene.add_ground(altitude=0) # Add a ground
16 actor_builder = scene.create_actor_builder()
17 actor_builder.add_box_collision(half_size=[0.5, 0.5, 0.5])
18 actor_builder.add_box_visual(half_size=[0.5, 0.5, 0.5], color=[1., 0., 0.])
19 box = actor_builder.build(name='box') # Add a box
20 box.set_pose(sapien.Pose(p=[0, 0, 0.5]))
21
22
23 # Add some lights so that you can observe the scene
24 scene.set_ambient_light([0.5, 0.5, 0.5])
25 scene.add_directional_light([0, 1, -1], [0.5, 0.5, 0.5])
26
27 viewer = Viewer(renderer) # Create a viewer (window)
28 viewer.set_scene(scene) # Bind the viewer and the scene
29
30 # The coordinate frame in Sapien is: x(forward), y(left), z(upward)
31 # The principle axis of the camera is the x-axis
32 viewer.set_camera_xyz(x=-4, y=0, z=2)
33 # The rotation of the free camera is represented as [roll(x), pitch(-y), yaw(-z)]
34 # The camera now looks at the origin
35 viewer.set_camera_rpy(r=0, p=-np.arctan2(2, 4), y=0)
36 viewer.window.set_camera_parameters(near=0.05, far=100, fovy=1)
37
38 while not viewer.closed: # Press key q to quit
39 scene.step() # Simulate the world
40 scene.update_render() # Update the world to the renderer
41 viewer.render()
42
43
44if __name__ == '__main__':
45 main()