Skip to content

Commit

Permalink
Merge pull request #643 from StanfordVL/fix-examples
Browse files Browse the repository at this point in the history
Fixes for all example scripts
  • Loading branch information
cgokmen authored Mar 17, 2024
2 parents b22e60a + 216c202 commit 93abbea
Show file tree
Hide file tree
Showing 28 changed files with 325 additions and 171 deletions.
4 changes: 2 additions & 2 deletions omnigibson/envs/env_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -558,7 +558,7 @@ def reset(self):
og.sim.step()

# Grab and return observations
obs, obs_info = self.get_obs()
obs, _ = self.get_obs()

if self._loaded:
# Sanity check to make sure received observations match expected observation space
Expand Down Expand Up @@ -598,7 +598,7 @@ def reset(self):
raise ValueError("Observation space does not match returned observations!")


return obs, obs_info
return obs

@property
def episode_steps(self):
Expand Down
4 changes: 2 additions & 2 deletions omnigibson/examples/learning/navigation_policy_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@
except ModuleNotFoundError:
og.log.error("torch, stable-baselines3, or tensorboard is not installed. "
"See which packages are missing, and then run the following for any missing packages:\n"
"pip install torch\n"
"pip install stable-baselines3==1.7.0\n"
"pip install stable-baselines3[extra]\n"
"pip install tensorboard\n"
"pip install shimmy>=0.2.1\n"
"Also, please update gym to >=0.26.1 after installing sb3: pip install gym>=0.26.1")
exit(1)

Expand Down
49 changes: 29 additions & 20 deletions omnigibson/examples/object_states/attachment_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,24 +32,31 @@ def main(random_selection=False, headless=False, short_exec=False):
name="shelf_back_panel",
category="shelf_back_panel",
model="gjsnrt",
bounding_box=[0.8, 2.02, 0.02],
position=[0, 0, 0.01],
fixed_base=True,
abilities={"attachable": {}},
))
idx += 1

xs = [-0.4, 0.4]
for i in range(2):
obj_cfgs.append(dict(
type="DatasetObject",
name=f"shelf_side_{i}",
category="shelf_side",
model="bxfkjj",
bounding_box=[0.03, 2.02, 0.26],
position=[xs[i], 0, base_z + delta_z * idx],
abilities={"attachable": {}},
))
idx += 1
obj_cfgs.append(dict(
type="DatasetObject",
name=f"shelf_side_left",
category="shelf_side",
model="bxfkjj",
position=[-0.4, 0, base_z + delta_z * idx],
abilities={"attachable": {}},
))
idx += 1

obj_cfgs.append(dict(
type="DatasetObject",
name=f"shelf_side_right",
category="shelf_side",
model="yujrmw",
position=[0.4, 0, base_z + delta_z * idx],
abilities={"attachable": {}},
))
idx += 1

ys = [-0.93, -0.61, -0.29, 0.03, 0.35, 0.68]
for i in range(6):
Expand All @@ -58,7 +65,6 @@ def main(random_selection=False, headless=False, short_exec=False):
name=f"shelf_shelf_{i}",
category="shelf_shelf",
model="ymtnqa",
bounding_box=[0.74, 0.023, 0.26],
position=[0, ys[i], base_z + delta_z * idx],
abilities={"attachable": {}},
))
Expand All @@ -69,7 +75,6 @@ def main(random_selection=False, headless=False, short_exec=False):
name="shelf_top_0",
category="shelf_top",
model="pfiole",
bounding_box=[0.74, 0.04, 0.26],
position=[0, 1.0, base_z + delta_z * idx],
abilities={"attachable": {}},
))
Expand All @@ -80,7 +85,6 @@ def main(random_selection=False, headless=False, short_exec=False):
name=f"shelf_baseboard",
category="shelf_baseboard",
model="hlhneo",
bounding_box=[0.742, 0.067, 0.02],
position=[0, -0.97884506, base_z + delta_z * idx],
abilities={"attachable": {}},
))
Expand All @@ -102,12 +106,17 @@ def main(random_selection=False, headless=False, short_exec=False):
shelf_baseboard = og.sim.scene.object_registry("name", "shelf_baseboard")
shelf_baseboard.set_position_orientation([0, -0.979, 0.26], [0, 0, 0, 1])
shelf_baseboard.keep_still()
shelf_baseboard.set_linear_velocity([-0.2, 0, 0])

shelf_baseboard.set_linear_velocity(np.array([-0.2, 0, 0]))

shelf_side_left = og.sim.scene.object_registry("name", "shelf_side_left")
shelf_side_left.set_position_orientation([-0.4, 0.0, 0.2], [0, 0, 0, 1])
shelf_side_left.keep_still()

input("\n\nShelf parts fall to their correct poses and get automatically attached to the back panel.\n"
"You can try to drag the shelf to hit the floor to break it apart. Press [ENTER] to continue.\n")
"You can try to drag (Shift + Left-CLICK + Drag) parts of the shelf to break it apart (you may need to zoom out and drag with a larger force).\n"
"Press [ENTER] to continue.\n")

for _ in range(1000):
for _ in range(5000):
og.sim.step()

og.shutdown()
Expand Down
2 changes: 1 addition & 1 deletion omnigibson/examples/object_states/dicing_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ def main(random_selection=False, headless=False, short_exec=False):
category="table_knife",
model="lrdmpf",
bounding_box=[0.401, 0.044, 0.009],
position=[0, 0, 10.0],
position=[0, 0, 20.0],
)

light0_cfg = dict(
Expand Down
10 changes: 1 addition & 9 deletions omnigibson/examples/object_states/object_state_texture_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,13 @@


def main():
# Create the scene config to load -- empty scene plus a light and a cabinet
# Create the scene config to load -- empty scene plus a cabinet
cfg = {
"scene": {
"type": "Scene",
"floor_plane_visible": True,
},
"objects": [
{
"type": "LightObject",
"name": "light",
"light_type": "Sphere",
"radius": 0.01,
"intensity": 1e8,
"position": [-2.0, -2.0, 1.0],
},
{
"type": "DatasetObject",
"name": "cabinet",
Expand Down
18 changes: 4 additions & 14 deletions omnigibson/examples/object_states/particle_applier_remover_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,16 +100,6 @@ def main(random_selection=False, headless=False, short_exec=False):
}
}

# Define objects to load: a light, table, and cloth
light_cfg = dict(
type="LightObject",
name="light",
light_type="Sphere",
radius=0.01,
intensity=1e8,
position=[-2.0, -2.0, 2.0],
)

table_cfg = dict(
type="DatasetObject",
name="table",
Expand All @@ -124,7 +114,7 @@ def main(random_selection=False, headless=False, short_exec=False):
"scene": {
"type": "Scene",
},
"objects": [light_cfg, table_cfg],
"objects": [table_cfg],
}

# Sanity check inputs: Remover + Adjacency + Fluid will not work because we are using a visual_only
Expand All @@ -148,7 +138,7 @@ def main(random_selection=False, headless=False, short_exec=False):
name="modifier",
category="dishtowel",
model="dtfspn",
bounding_box=[0.341, 0.466, 0.07],
bounding_box=[0.34245, 0.46798, 0.07],
visual_only=method_type == "Projection", # Non-fluid adjacency requires the object to have collision geoms active
abilities=abilities,
)
Expand Down Expand Up @@ -203,9 +193,9 @@ def main(random_selection=False, headless=False, short_exec=False):

# Move object in square around table
deltas = [
[150, np.array([-0.01, 0, 0])],
[130, np.array([-0.01, 0, 0])],
[60, np.array([0, -0.01, 0])],
[150, np.array([0.01, 0, 0])],
[130, np.array([0.01, 0, 0])],
[60, np.array([0, 0.01, 0])],
]
for t, delta in deltas:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ def main(random_selection=False, headless=False, short_exec=False):
name=f"plate{i}",
category="plate",
model="iawoof",
bounding_box=np.array([0.25, 0.25, 0.05]),
bounding_box=np.array([0.20, 0.20, 0.05]),
) for i in range(2)]

apple_cfgs = [dict(
Expand Down
2 changes: 1 addition & 1 deletion omnigibson/examples/object_states/slicing_demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ def main(random_selection=False, headless=False, short_exec=False):
category="table_knife",
model="lrdmpf",
bounding_box=[0.401, 0.044, 0.009],
position=[0, 0, 10.0],
position=[0, 0, 20.0],
)

light0_cfg = dict(
Expand Down
1 change: 0 additions & 1 deletion omnigibson/examples/objects/load_object_selector.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ def main(random_selection=False, headless=False, short_exec=False):
name="obj",
category=obj_category,
model=obj_model,
bounding_box=avg_category_spec.get(obj_category),
position=[0, 0, 50.0],
)

Expand Down
42 changes: 25 additions & 17 deletions omnigibson/examples/robots/advanced/ik_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,32 +38,32 @@ def main(random_selection=False, headless=False, short_exec=False):
programmatic_pos = True

# Import scene and robot (Fetch)
scene = Scene()
og.sim.import_scene(scene)

# Update the viewer camera's pose so that it points towards the robot
og.sim.viewer_camera.set_position_orientation(
position=np.array([4.32248, -5.74338, 6.85436]),
orientation=np.array([0.39592, 0.13485, 0.29286, 0.85982]),
)

scene_cfg = {"type": "Scene"}
# Create Fetch robot
# Note that since we only care about IK functionality, we fix the base (this also makes the robot more stable)
# (any object can also have its fixed_base attribute set to True!)
# Note that since we're going to be setting joint position targets, we also need to make sure the robot's arm joints
# (which includes the trunk) are being controlled using joint positions
robot = Fetch(
prim_path="/World/robot",
name="robot",
fixed_base=True,
controller_config={
robot_cfg = {
"type": "Fetch",
"fixed_base": True,
"controller_config": {
"arm_0": {
"name": "JointController",
"name": "NullJointController",
"motor_type": "position",
}
}
}
cfg = dict(scene=scene_cfg, robots=[robot_cfg])
env = og.Environment(configs=cfg)

# Update the viewer camera's pose so that it points towards the robot
og.sim.viewer_camera.set_position_orientation(
position=np.array([4.32248, -5.74338, 6.85436]),
orientation=np.array([0.39592, 0.13485, 0.29286, 0.85982]),
)
og.sim.import_object(robot)

robot = env.robots[0]

# Set robot base at the origin
robot.set_position_orientation(np.array([0, 0, 0]), np.array([0, 0, 0, 1]))
Expand All @@ -73,6 +73,9 @@ def main(random_selection=False, headless=False, short_exec=False):
og.sim.step()
# Make sure none of the joints are moving
robot.keep_still()
# Since this demo aims to showcase how users can directly control the robot with IK,
# we will need to disable the built-in controllers in OmniGibson
robot.control_enabled = False

# Create the IK solver -- note that we are controlling both the trunk and the arm since both are part of the
# controllable kinematic chain for the end-effector!
Expand All @@ -91,7 +94,12 @@ def execute_ik(pos, quat=None, max_iter=100):
joint_pos = ik_solver.solve(
target_pos=pos,
target_quat=quat,
tolerance_pos=0.002,
tolerance_quat=0.01,
weight_pos=20.0,
weight_quat=0.05,
max_iterations=max_iter,
initial_joint_pos=robot.get_joint_positions()[control_idx],
)
if joint_pos is not None:
og.log.info("Solution found. Setting new arm configuration.")
Expand Down Expand Up @@ -185,7 +193,7 @@ def print_message():
print("Move the marker to a desired position to query IK and press ENTER")
print("W/S: move marker further away or closer to the robot")
print("A/D: move marker to the left or the right of the robot")
print("T/G: move marker up and down")
print("UP/DOWN: move marker up and down")
print("ESC: quit")


Expand Down
2 changes: 2 additions & 0 deletions omnigibson/examples/robots/all_robots_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@ def main(random_selection=False, headless=False, short_exec=False):
# Then apply random actions for a bit
for _ in range(30):
action = np.random.uniform(-1, 1, robot.action_dim)
if robot_name == "Tiago":
action[robot.base_action_idx] = np.random.uniform(-0.1, 0.1, len(robot.base_action_idx))
for _ in range(10):
env.step(action)

Expand Down
2 changes: 2 additions & 0 deletions omnigibson/object_states/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,12 @@
from omnigibson.object_states.overlaid import Overlaid
from omnigibson.object_states.particle_modifier import ParticleRemover, ParticleApplier
from omnigibson.object_states.particle_source_or_sink import ParticleSource, ParticleSink
from omnigibson.object_states.particle import ParticleRequirement
from omnigibson.object_states.pose import Pose
from omnigibson.object_states.robot_related_states import IsGrasping, ObjectsInFOVOfRobot
from omnigibson.object_states.saturated import Saturated
from omnigibson.object_states.slicer_active import SlicerActive
from omnigibson.object_states.sliceable import SliceableRequirement
from omnigibson.object_states.temperature import Temperature
from omnigibson.object_states.toggle import ToggledOn
from omnigibson.object_states.touching import Touching
Expand Down
4 changes: 2 additions & 2 deletions omnigibson/object_states/attached_to.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@
m.DEFAULT_POSITION_THRESHOLD = 0.05 # 5cm
m.DEFAULT_ORIENTATION_THRESHOLD = np.deg2rad(5.0) # 5 degrees
m.DEFAULT_JOINT_TYPE = JointType.JOINT_FIXED
m.DEFAULT_BREAK_FORCE = 10000 # Newton
m.DEFAULT_BREAK_TORQUE = 10000 # Newton-Meter
m.DEFAULT_BREAK_FORCE = 1000 # Newton
m.DEFAULT_BREAK_TORQUE = 1000 # Newton-Meter


class AttachedTo(RelativeObjectState, BooleanStateMixin, ContactSubscribedStateMixin, JointBreakSubscribedStateMixin, LinkBasedStateMixin):
Expand Down
Loading

0 comments on commit 93abbea

Please sign in to comment.