Skip to content

Commit

Permalink
[xr] Initial commit
Browse files Browse the repository at this point in the history
  • Loading branch information
wensi-ai committed Nov 8, 2023
1 parent e5385ed commit ad42ad5
Show file tree
Hide file tree
Showing 14 changed files with 1,576 additions and 57 deletions.
1 change: 1 addition & 0 deletions omnigibson/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,7 @@ def create_app():
from omni.isaac.core.utils.extensions import enable_extension
enable_extension("omni.flowusd")
enable_extension("omni.particle.system.bundle")
enable_extension("omni.kit.xr.profile.vr")

# Additional import for windows
if os.name == "nt":
Expand Down
105 changes: 105 additions & 0 deletions omnigibson/examples/xr/hand_tracking_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
"""
Example script for vr system.
"""
import omnigibson as og
from omnigibson.utils.xr_utils import VRSys
from omnigibson.utils.ui_utils import choose_from_options

# You can set this to True to visualize the landmarks of the hands!
DEBUG_MODE = True

ROBOTS = {
"Behaviorbot": "Humanoid robot with two hands (default)",
"FrankaAllegro": "Franka Panda with Allegro hand",
}

def main():
robot_name = choose_from_options(options=ROBOTS, name="robot")

# Create the config for generating the environment we want
scene_cfg = {"type": "Scene"}
robot0_cfg = {
"type": robot_name,
"obs_modalities": ["rgb", "depth", "normal", "scan", "occupancy_grid"],
"action_normalize": False,
}
object_cfg = [
{
"type": "DatasetObject",
"prim_path": "/World/breakfast_table",
"name": "breakfast_table",
"category": "breakfast_table",
"model": "kwmfdg",
"bounding_box": [2, 1, 0.4],
"position": [0.8, 0, 0.3],
"orientation": [0, 0, 0.707, 0.707],
},
{
"type": "DatasetObject",
"prim_path": "/World/apple",
"name": "apple",
"category": "apple",
"model": "omzprq",
"position": [0.6, 0.1, 0.5],
},
{
"type": "DatasetObject",
"prim_path": "/World/banana",
"name": "banana",
"category": "banana",
"model": "znakxm",
"position": [0.6, -0.1, 0.5],
},
]
if DEBUG_MODE:
# Add the marker to visualize hand tracking waypoints
object_cfg.extend([{
"type": "PrimitiveObject",
"prim_path": f"/World/marker_{i}",
"name": f"marker_{i}",
"primitive_type": "Cube",
"size": 0.01,
"visual_only": True,
"rgba": [0.0, 1.0, 0.0, 1.0],
} for i in range(52)])

cfg = dict(scene=scene_cfg, robots=[robot0_cfg], objects=object_cfg)
# Create the environment
env = og.Environment(configs=cfg, action_timestep=1/60., physics_timestep=1/240.)
env.reset()
# Start vrsys
vr_robot = env.robots[0]
vrsys = VRSys(vr_robot=vr_robot, use_hand_tracking=True)
vrsys.start()
# set headset position to be 1m above ground and facing +x direction
head_init_transform = vrsys.og2xr(pos=[0, 0, 1], orn=[0, 0, 0, 1])
vrsys.vr_profile.set_physical_world_to_world_anchor_transform_to_match_xr_device(head_init_transform, vrsys.hmd)

# get the objects
if DEBUG_MODE:
markers = [env.scene.object_registry("name", f"marker_{i}") for i in range(52)]

# main simulation loop
for _ in range(10000):
if og.sim.is_playing():
vr_data = vrsys.step()
if DEBUG_MODE:
if "left" in vr_data["hand_data"] and "raw" in vr_data["hand_data"]["left"]:
for i in range(26):
pos = vr_data["hand_data"]["left"]["raw"]["pos"][i]
orn = vr_data["hand_data"]["left"]["raw"]["orn"][i]
markers[i].set_position_orientation(pos, orn)
if "right" in vr_data["hand_data"] and "raw" in vr_data["hand_data"]["right"]:
for i in range(26):
pos = vr_data["hand_data"]["right"]["raw"]["pos"][i]
orn = vr_data["hand_data"]["right"]["raw"]["orn"][i]
markers[i + 26].set_position_orientation(pos, orn)
action = vr_robot.gen_action_from_vr_data(vr_data)
env.step(action)

# Shut down the environment cleanly at the end
vrsys.stop()
env.close()

if __name__ == "__main__":
main()
140 changes: 140 additions & 0 deletions omnigibson/examples/xr/robot_teleoperate_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,140 @@
"""
Example script for using VR controller to teleoperate a robot.
"""
import omnigibson as og
from omnigibson.utils.xr_utils import VRSys
from omnigibson.utils.ui_utils import choose_from_options

ROBOTS = {
"FrankaPanda": "Franka Emika Panda (default)",
"Fetch": "Mobile robot with one arm",
"Tiago": "Mobile robot with two arms",
}


def main():
robot_name = choose_from_options(options=ROBOTS, name="robot")
# Create the config for generating the environment we want
scene_cfg = dict()
scene_cfg["type"] = "Scene"
# Add the robot we want to load
robot0_cfg = {
"type": robot_name,
"obs_modalities": ["rgb", "depth", "seg_instance", "normal", "scan", "occupancy_grid"],
"action_normalize": False,
"grasping_mode": "assisted",
"controller_config": {
"arm_0": {
"name": "InverseKinematicsController",
"mode": "pose_absolute_ori",
"motor_type": "position",
},
"gripper_0": {
"name": "MultiFingerGripperController",
"command_input_limits": (0.0, 1.0),
"mode": "smooth",
"inverted": True
}
}
}
object_cfg = [
{
"type": "DatasetObject",
"prim_path": "/World/breakfast_table",
"name": "breakfast_table",
"category": "breakfast_table",
"model": "kwmfdg",
"bounding_box": [2, 1, 0.4],
"position": [0.8, 0, 0.3],
"orientation": [0, 0, 0.707, 0.707],
},
{
"type": "DatasetObject",
"prim_path": "/World/frail",
"name": "frail",
"category": "frail",
"model": "zmjovr",
"scale": [2, 2, 2],
"position": [0.6, -0.3, 0.5],
},
{
"type": "DatasetObject",
"prim_path": "/World/toy_figure1",
"name": "toy_figure1",
"category": "toy_figure",
"model": "issvzv",
"scale": [0.75, 0.75, 0.75],
"position": [0.6, 0, 0.5],
},
{
"type": "DatasetObject",
"prim_path": "/World/toy_figure2",
"name": "toy_figure2",
"category": "toy_figure",
"model": "nncqfn",
"scale": [0.75, 0.75, 0.75],
"position": [0.6, 0.1, 0.5],
},
{
"type": "DatasetObject",
"prim_path": "/World/toy_figure3",
"name": "toy_figure3",
"category": "toy_figure",
"model": "eulekw",
"scale": [0.25, 0.25, 0.25],
"position": [0.6, 0.2, 0.5],
},
{
"type": "DatasetObject",
"prim_path": "/World/toy_figure4",
"name": "toy_figure4",
"category": "toy_figure",
"model": "yxiksm",
"scale": [0.25, 0.25, 0.25],
"position": [0.6, 0.3, 0.5],
},
{
"type": "DatasetObject",
"prim_path": "/World/toy_figure5",
"name": "toy_figure5",
"category": "toy_figure",
"model": "wvpqbf",
"scale": [0.75, 0.75, 0.75],
"position": [0.6, 0.4, 0.5],
},
]
cfg = dict(scene=scene_cfg, robots=[robot0_cfg], objects=object_cfg)

# Create the environment
env = og.Environment(configs=cfg, action_timestep=1/60., physics_timestep=1/240.)
env.reset()
# update viewer camera pose
og.sim.viewer_camera.set_position_orientation([-0.22, 0.99, 1.09], [-0.14, 0.47, 0.84, -0.23])

# Start vrsys
vr_robot = env.robots[0]
vrsys = VRSys(system="SteamVR", vr_robot=vr_robot, show_controller=True, disable_display_output=True, align_anchor_to_robot_base=True)
vrsys.start()
# tracker variable of whether the robot is attached to the VR system
prev_robot_attached = False
# main simulation loop
for _ in range(10000):
if og.sim.is_playing():
vr_data = vrsys.step()
if vr_data["robot_attached"] == True and prev_robot_attached == False:
if vr_robot.model_name == "Tiago":
robot_eef_position = vr_robot.links[vr_robot.eef_link_names["right"]].get_position()
else:
robot_eef_position = vr_robot.links[vr_robot.eef_link_names[vr_robot.default_arm]].get_position()
base_rotation = vr_robot.get_orientation()
vrsys.snap_device_to_robot_eef(robot_eef_position=robot_eef_position, base_rotation=base_rotation)
else:
action = vr_robot.gen_action_from_vr_data(vr_data)
env.step(action)
prev_robot_attached = vr_data["robot_attached"]
# Shut down the environment cleanly at the end
vrsys.stop()
env.close()

if __name__ == "__main__":
main()
45 changes: 45 additions & 0 deletions omnigibson/examples/xr/vr_simple_demo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
"""
Example script for interacting with OmniGibson scenes with VR and Behaviorbot.
"""
import omnigibson as og
from omnigibson.utils.xr_utils import VRSys

def main():
# Create the config for generating the environment we want
scene_cfg = dict()
scene_cfg["type"] = "InteractiveTraversableScene"
scene_cfg["scene_model"] = "Rs_int"
robot0_cfg = dict()
robot0_cfg["type"] = "Behaviorbot"
robot0_cfg["controller_config"] = {
"gripper_0": {"command_input_limits": "default"},
"gripper_1": {"command_input_limits": "default"},
}
cfg = dict(scene=scene_cfg, robots=[robot0_cfg])

# Create the environment
env = og.Environment(configs=cfg, action_timestep=1/60., physics_timestep=1/240.)
env.reset()
# start vrsys
vr_robot = env.robots[0]
vrsys = VRSys(system="SteamVR", vr_robot=vr_robot, enable_touchpad_movement=True)
vrsys.start()
# set headset position to be 1m above ground and facing +x
head_init_transform = vrsys.og2xr(pos=[0, 0, 1], orn=[0, 0, 0, 1])
vrsys.vr_profile.set_physical_world_to_world_anchor_transform_to_match_xr_device(head_init_transform, vrsys.hmd)

# main simulation loop
for _ in range(10000):
if og.sim.is_playing():
# step the VR system to get the latest data from VR runtime
vr_data = vrsys.step()
# generate robot action and step the environment
action = vr_robot.gen_action_from_vr_data(vr_data)
env.step(action)

# Shut down the environment cleanly at the end
vrsys.stop()
env.close()

if __name__ == "__main__":
main()
1 change: 1 addition & 0 deletions omnigibson/robots/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,3 +11,4 @@
from omnigibson.robots.two_wheel_robot import TwoWheelRobot
from omnigibson.robots.franka import FrankaPanda
from omnigibson.robots.franka_allegro import FrankaAllegro
from omnigibson.robots.behaviorbot import Behaviorbot
Loading

0 comments on commit ad42ad5

Please sign in to comment.