Isaac Gym utils
Table of Contents
Control of robotic manipulators
Inverse kinematics using damped least squares method
This implementation attempts to unify under a single and reusable function the whole set of procedures used to calculate the inverse kinematics of a robotic manipulator shown in Isaac Gym’s example: Franka IK Picking (franka_cube_ik_osc.py
)
\(\Delta\theta = J^T (JJ^T + \lambda^2 I)^{-1} \, \vec{e}\)
where
API
- skrl.utils.isaacgym_utils.ik(jacobian_end_effector: torch.Tensor, current_position: torch.Tensor, current_orientation: torch.Tensor, goal_position: torch.Tensor, goal_orientation: Optional[torch.Tensor] = None, damping_factor: float = 0.05, squeeze_output: bool = True) torch.Tensor
Inverse kinematics using damped least squares method
- Parameters
jacobian_end_effector (torch.Tensor) – End effector’s jacobian
current_position (torch.Tensor) – End effector’s current position
current_orientation (torch.Tensor) – End effector’s current orientation
goal_position (torch.Tensor) – End effector’s goal position
goal_orientation (torch.Tensor or None) – End effector’s goal orientation (default: None)
damping_factor (float) – Damping factor (default: 0.05)
squeeze_output (bool) – Squeeze output (default: True)
- Returns
Change in joint angles
- Return type
Web viewer for development without X server
This library provides an API for instantiating a lightweight web viewer useful, mostly, for designing Isaac Gym environments in remote workstations or docker containers without X server
Gestures and actions
Gestures / actions |
Key |
Mouse |
---|---|---|
Orbit (rotate view around a point) |
Alt |
Left click |
Pan (rotate view around itself) |
Right click |
|
Walk mode (move view linearly to the current alignment) |
Middle click |
|
Zoom in/out |
Scroll wheel |
|
Freeze view |
V |
|
Toggle image type (color, depth) |
T |
Watch an animation of the gestures and actions in the following video
Requirements
The web viewer is build on top of Flask and requires the following package to be installed
pip install Flask
Also, to be launched in Visual Studio Code (Preview in Editor), the Live Preview - VS Code Extension must be installed
Basic usage
1import math
2from isaacgym import gymapi
3
4from skrl.utils import isaacgym_utils
5
6
7# create a web viewer instance
8web_viewer = isaacgym_utils.WebViewer()
9
10# configure and create simulation
11sim_params = gymapi.SimParams()
12sim_params.up_axis = gymapi.UP_AXIS_Z
13sim_params.gravity = gymapi.Vec3(0.0, 0.0, -9.8)
14sim_params.physx.solver_type = 1
15sim_params.physx.num_position_iterations = 4
16sim_params.physx.num_velocity_iterations = 1
17sim_params.physx.use_gpu = True
18sim_params.use_gpu_pipeline = True
19
20gym = gymapi.acquire_gym()
21sim = gym.create_sim(compute_device=0, graphics_device=0, type=gymapi.SIM_PHYSX, params=sim_params)
22
23# setup num_envs and env's grid
24num_envs = 1
25spacing = 2.0
26env_lower = gymapi.Vec3(-spacing, -spacing, 0.0)
27env_upper = gymapi.Vec3(spacing, 0.0, spacing)
28
29# add ground plane
30plane_params = gymapi.PlaneParams()
31plane_params.normal = gymapi.Vec3(0.0, 0.0, 1.0)
32gym.add_ground(sim, plane_params)
33
34envs = []
35cameras = []
36
37for i in range(num_envs):
38 # create env
39 env = gym.create_env(sim, env_lower, env_upper, int(math.sqrt(num_envs)))
40
41 # add sphere
42 pose = gymapi.Transform()
43 pose.p, pose.r = gymapi.Vec3(0.0, 0.0, 1.0), gymapi.Quat(0.0, 0.0, 0.0, 1.0)
44 gym.create_actor(env, gym.create_sphere(sim, 0.2, None), pose, "sphere", i, 0)
45
46 # add camera
47 cam_props = gymapi.CameraProperties()
48 cam_props.width, cam_props.height = 300, 300
49 cam_handle = gym.create_camera_sensor(env, cam_props)
50 gym.set_camera_location(cam_handle, env, gymapi.Vec3(1, 1, 1), gymapi.Vec3(0, 0, 0))
51
52 envs.append(env)
53 cameras.append(cam_handle)
54
55# setup web viewer
56web_viewer.setup(gym, sim, envs, cameras)
57
58gym.prepare_sim(sim)
59
60
61for i in range(100000):
62 gym.simulate(sim)
63
64 # render the scene
65 web_viewer.render(fetch_results=True,
66 step_graphics=True,
67 render_all_camera_sensors=True,
68 wait_for_page_load=True)
API
- class skrl.utils.isaacgym_utils.WebViewer(host: str = '127.0.0.1', port: int = 5000)
Bases:
object
- _route_index() flask.Response
Render the web page
- Returns
Flask response
- Return type
flask.Response
- _route_input_event() flask.Response
Handle keyboard and mouse input
- Returns
Flask response
- Return type
flask.Response
- _route_stream() flask.Response
Stream the image to the web page
- Returns
Flask response
- Return type
flask.Response
- render(fetch_results: bool = True, step_graphics: bool = True, render_all_camera_sensors: bool = True, wait_for_page_load: bool = True) None
Render and get the image from the current camera
This function must be called after the simulation is stepped (post_physics_step). The following Isaac Gym functions are called before get the image. Their calling can be skipped by setting the corresponding argument to False
fetch_results
step_graphics
render_all_camera_sensors
- Parameters
fetch_results (bool) – Call Gym.fetch_results method (default: True)
step_graphics (bool) – Call Gym.step_graphics method (default: True)
render_all_camera_sensors (bool) – Call Gym.render_all_camera_sensors method (default: True)
wait_for_page_load (bool) – Wait for the page to load (default: True)