Skip to content

Commit

Permalink
Merge pull request #618 from StanfordVL/telemoma
Browse files Browse the repository at this point in the history
Telemoma
  • Loading branch information
cgokmen authored Mar 18, 2024
2 parents 4b68a82 + 408694c commit 40e2ad8
Show file tree
Hide file tree
Showing 14 changed files with 258 additions and 717 deletions.
3 changes: 1 addition & 2 deletions omnigibson/configs/fetch_behavior.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ robots:
rigid_trunk: false
default_trunk_offset: 0.365
default_arm_pose: diagonal30
reset_joint_pos: tuck
default_reset_mode: tuck
sensor_config:
VisionSensor:
sensor_kwargs:
Expand All @@ -62,7 +62,6 @@ robots:
name: DifferentialDriveController
arm_0:
name: InverseKinematicsController
kv: 2.0
gripper_0:
name: MultiFingerGripperController
mode: binary
Expand Down
6 changes: 4 additions & 2 deletions omnigibson/envs/env_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
from omnigibson.utils.ui_utils import create_module_logger
from omnigibson.utils.python_utils import assert_valid_key, merge_nested_dicts, create_class_from_registry_and_config,\
Recreatable
from omnigibson.macros import gm


# Create module logger
Expand Down Expand Up @@ -202,8 +203,9 @@ def _load_scene(self):
og.sim.import_scene(scene)

# Set the rendering settings
og.sim.viewer_width = self.render_config["viewer_width"]
og.sim.viewer_height = self.render_config["viewer_height"]
if gm.RENDER_VIEWER_CAMERA:
og.sim.viewer_width = self.render_config["viewer_width"]
og.sim.viewer_height = self.render_config["viewer_height"]
og.sim.device = self.device

assert og.sim.is_stopped(), "Simulator must be stopped after loading scene!"
Expand Down
98 changes: 0 additions & 98 deletions omnigibson/examples/teleoperation/hand_tracking_demo.py

This file was deleted.

89 changes: 33 additions & 56 deletions omnigibson/examples/teleoperation/robot_teleoperate_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,20 +9,34 @@
"Fetch": "Mobile robot with one arm",
"Tiago": "Mobile robot with two arms",
}

SYSTEMS = {
"Keyboard": "Keyboard (default)",
"SteamVR": "SteamVR with HTC VIVE through OmniverseXR plugin",
"Oculus": "Oculus Reader with Quest 2",
"SpaceMouse": "Space Mouse",
TELEOP_METHOD = {
"keyboard": "Keyboard (default)",
"spacemouse": "SpaceMouse",
"oculus": "Oculus Quest",
"vision": "Human Keypoints with Camera",
}


def main():
teleop_system = choose_from_options(options=SYSTEMS, name="system")
from omnigibson.utils.teleop_utils import TeleopSystem
from telemoma.utils.camera_utils import RealSenseCamera
from telemoma.configs.base_config import teleop_config

robot_name = choose_from_options(options=ROBOTS, name="robot")
arm_teleop_method = choose_from_options(options=TELEOP_METHOD, name="robot arm teleop method")
if robot_name != "FrankaPanda":
base_teleop_method = choose_from_options(options=TELEOP_METHOD, name="robot base teleop method")
else:
base_teleop_method = "keyboard" # Dummy value since FrankaPanda does not have a base
# Generate teleop config
teleop_config.arm_left_controller = arm_teleop_method
teleop_config.arm_right_controller = arm_teleop_method
teleop_config.base_controller = base_teleop_method
teleop_config.interface_kwargs["keyboard"] = {"arm_speed_scaledown": 0.04}
teleop_config.interface_kwargs["spacemouse"] = {"arm_speed_scaledown": 0.04}
if arm_teleop_method == "vision" or base_teleop_method == "vision":
teleop_config.interface_kwargs["vision"] = {"camera": RealSenseCamera()}

# Create the config for generating the environment we want
env_cfg = {"action_timestep": 1 / 60., "physics_timestep": 1 / 300.}
scene_cfg = {"type": "Scene"}
# Add the robot we want to load
robot_cfg = {
Expand All @@ -36,14 +50,12 @@ def main():
for arm in arms:
robot_cfg["controller_config"][f"arm_{arm}"] = {
"name": "InverseKinematicsController",
"mode": "pose_absolute_ori",
"motor_type": "position"
"command_input_limits": None,
}
robot_cfg["controller_config"][f"gripper_{arm}"] = {
"name": "MultiFingerGripperController",
"command_input_limits": (0.0, 1.0),
"mode": "smooth",
"inverted": True
}
object_cfg = [
{
Expand All @@ -63,7 +75,7 @@ def main():
"category": "frail",
"model": "zmjovr",
"scale": [2, 2, 2],
"position": [0.6, -0.3, 0.5],
"position": [0.6, -0.35, 0.5],
},
{
"type": "DatasetObject",
Expand All @@ -81,7 +93,7 @@ def main():
"category": "toy_figure",
"model": "nncqfn",
"scale": [0.75, 0.75, 0.75],
"position": [0.6, 0.1, 0.5],
"position": [0.6, 0.15, 0.5],
},
{
"type": "DatasetObject",
Expand All @@ -90,63 +102,28 @@ def main():
"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(env=env_cfg, scene=scene_cfg, robots=[robot_cfg], objects=object_cfg)
cfg = dict(scene=scene_cfg, robots=[robot_cfg], objects=object_cfg)

# Create the environment
env = og.Environment(configs=cfg)
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 teleoperation system
robot = env.robots[0]

# Initialize teleoperation system
if teleop_system == "SteamVR":
from omnigibson.utils.teleop_utils import OVXRSystem as TeleopSystem
elif teleop_system == "Oculus":
from omnigibson.utils.teleop_utils import OculusReaderSystem as TeleopSystem
elif teleop_system == "SpaceMouse":
from omnigibson.utils.teleop_utils import SpaceMouseSystem as TeleopSystem
elif teleop_system == "Keyboard":
from omnigibson.utils.teleop_utils import KeyboardSystem as TeleopSystem
teleop_sys = TeleopSystem(robot=robot, disable_display_output=True, align_anchor_to_robot_base=True)
teleop_sys = TeleopSystem(config=teleop_config, robot=robot, show_control_marker=True)
teleop_sys.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():
teleop_sys.update()
if teleop_sys.teleop_data.robot_attached and not prev_robot_attached:
teleop_sys.reset_transform_mapping()
if robot_name == "Tiago":
teleop_sys.reset_transform_mapping("left")
else:
action = teleop_sys.teleop_data_to_action()
env.step(action)
prev_robot_attached = teleop_sys.teleop_data.robot_attached
action = teleop_sys.get_action(teleop_sys.get_obs())
env.step(action)

# Shut down the environment cleanly at the end
teleop_sys.stop()
env.close()
Expand Down
15 changes: 6 additions & 9 deletions omnigibson/examples/teleoperation/vr_simple_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,24 +6,21 @@

def main():
# Create the config for generating the environment we want
env_cfg = {"action_timestep": 1 / 60., "physics_timestep": 1 / 120.}
scene_cfg = {"type": "InteractiveTraversableScene", "scene_model": "Rs_int"}
scene_cfg = {"type": "Scene"} #"InteractiveTraversableScene", "scene_model": "Rs_int"}
robot0_cfg = {
"type": "BehaviorRobot",
"type": "Tiago",
"controller_config": {
"gripper_0": {"command_input_limits": "default"},
"gripper_1": {"command_input_limits": "default"},
"gripper_left": {"command_input_limits": "default"},
"gripper_right": {"command_input_limits": "default"},
}
}
cfg = dict(env=env_cfg, scene=scene_cfg, robots=[robot0_cfg])
cfg = dict(scene=scene_cfg, robots=[robot0_cfg])

# Create the environment
env = og.Environment(configs=cfg)
env.reset()
# start vrsys
vrsys = OVXRSystem(robot=env.robots[0], show_control_marker=False, system="SteamVR", enable_touchpad_movement=True)
# We want a lower movement speed for controlling with VR headset
vrsys.base_movement_speed = 0.03
vrsys = OVXRSystem(robot=env.robots[0], show_control_marker=False, system="SteamVR", align_anchor_to_robot_base=True)
vrsys.start()
# set headset position to be 1m above ground and facing +x
vrsys.set_initial_transform(pos=[0, 0, 1], orn=[0, 0, 0, 1])
Expand Down
Loading

0 comments on commit 40e2ad8

Please sign in to comment.