Skip to content

Commit

Permalink
Make Tiago run OK on the GPU
Browse files Browse the repository at this point in the history
  • Loading branch information
cgokmen committed Sep 28, 2023
1 parent 0215590 commit 0d4f235
Show file tree
Hide file tree
Showing 2 changed files with 50 additions and 52 deletions.
10 changes: 0 additions & 10 deletions omnigibson/action_primitives/starter_semantic_action_primitives.py
Original file line number Diff line number Diff line change
Expand Up @@ -244,9 +244,6 @@ def __init__(self, task, scene, robot, add_context=False):

self.robot_copy = self._load_robot_copy(robot)

if self.robot_model == "Tiago":
self._setup_tiago()

def with_context(self, action):
if not self.add_context:
return action
Expand All @@ -266,13 +263,6 @@ def with_context(self, action):
print(context)
return action, context

# Disable grasping frame for Tiago robot (Should be cleaned up in the future)
def _setup_tiago(self):
for link in self.robot.links.values():
for mesh in link.collision_meshes.values():
if "grasping_frame" in link.prim_path:
mesh.collision_enabled = False

@staticmethod
def _load_robot_copy(robot):
robot_copy = RobotCopy()
Expand Down
92 changes: 50 additions & 42 deletions tests/test_symbolic_primitives.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,49 +27,57 @@ def start_env():
},
"robots": [
{
"type": "Fetch",
"obs_modalities": [
"scan",
"rgb",
"depth"
],
"scale": 1,
"self_collisions": True,
"action_normalize": False,
"action_type": "continuous",
"grasping_mode": "sticky",
"disable_grasp_handling": True,
"rigid_trunk": False,
"default_trunk_offset": 0.365,
"default_arm_pose": "diagonal30",
"reset_joint_pos": "tuck",
"controller_config": {
"base": {
"name": "DifferentialDriveController"
},
"arm_0": {
"name": "JointController",
"motor_type": "position",
"command_input_limits": None,
"command_output_limits": None,
"use_delta_commands": False
},
"gripper_0": {
"name": "JointController",
"motor_type": "position",
"command_input_limits": [
-1,
1
],
"command_output_limits": None,
"use_delta_commands": True,
"use_single_command": True
},
"camera": {
"name": "JointController",
"use_delta_commands": False
"type": "Tiago",
"obs_modalities": ["scan", "rgb", "depth"],
"scale": 1.0,
"self_collisions": True,
"action_normalize": False,
"action_type": "continuous",
"grasping_mode": "sticky",
"rigid_trunk": False,
"default_arm_pose": "diagonal30",
"default_trunk_offset": 0.365,
"controller_config": {
"base": {
"name": "JointController",
"motor_type": "velocity"
},
"arm_left": {
"name": "JointController",
"motor_type": "position",
"command_input_limits": None,
"command_output_limits": None,
"use_delta_commands": False
},
"arm_right": {
"name": "JointController",
"motor_type": "position",
"command_input_limits": None,
"command_output_limits": None,
"use_delta_commands": False
},
"gripper_left": {
"name": "JointController",
"motor_type": "position",
"command_input_limits": [-1, 1],
"command_output_limits": None,
"use_delta_commands": True,
"use_single_command": True
},
"gripper_right": {
"name": "JointController",
"motor_type": "position",
"command_input_limits": [-1, 1],
"command_output_limits": None,
"use_delta_commands": True,
"use_single_command": True
},
"camera": {
"name": "JointController",
"motor_type": "velocity",
"use_delta_commands": False
}
}
}
}
],
"objects": [
Expand Down

0 comments on commit 0d4f235

Please sign in to comment.