Skip to content

Commit

Permalink
Merge pull request #641 from StanfordVL/misc-fixes
Browse files Browse the repository at this point in the history
Migration of non-hacky changes from `feat/sampling_2024`
  • Loading branch information
ChengshuLi authored Mar 11, 2024
2 parents 3830c52 + 44058b2 commit 8105c2a
Show file tree
Hide file tree
Showing 18 changed files with 123 additions and 95 deletions.
22 changes: 12 additions & 10 deletions omnigibson/envs/env_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -234,11 +234,12 @@ def _load_robots(self):
og.sim.import_object(robot)
robot.set_position_orientation(position=position, orientation=orientation)

# Auto-initialize all robots
og.sim.play()
self.scene.reset()
self.scene.update_initial_state()
og.sim.stop()
if len(self.robots_config) > 0:
# Auto-initialize all robots
og.sim.play()
self.scene.reset()
self.scene.update_initial_state()
og.sim.stop()

assert og.sim.is_stopped(), "Simulator must be stopped after loading robots!"

Expand All @@ -264,11 +265,12 @@ def _load_objects(self):
og.sim.import_object(obj)
obj.set_position_orientation(position=position, orientation=orientation)

# Auto-initialize all objects
og.sim.play()
self.scene.reset()
self.scene.update_initial_state()
og.sim.stop()
if len(self.objects_config) > 0:
# Auto-initialize all objects
og.sim.play()
self.scene.reset()
self.scene.update_initial_state()
og.sim.stop()

assert og.sim.is_stopped(), "Simulator must be stopped after loading objects!"

Expand Down
1 change: 1 addition & 0 deletions omnigibson/maps/segmentation_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import numpy as np

from PIL import Image
Image.MAX_IMAGE_PIXELS = None

import omnigibson as og
from omnigibson.macros import gm
Expand Down
1 change: 1 addition & 0 deletions omnigibson/maps/traversable_map.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import cv2
import numpy as np
from PIL import Image
Image.MAX_IMAGE_PIXELS = None

from omnigibson.maps.map_base import BaseMap
from omnigibson.utils.ui_utils import create_module_logger
Expand Down
7 changes: 5 additions & 2 deletions omnigibson/object_states/link_based_state_mixin.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
from omnigibson.object_states.object_state_base import BaseObjectState
from omnigibson.utils.ui_utils import create_module_logger
from omnigibson.utils.python_utils import classproperty
from omnigibson.prims.cloth_prim import ClothPrim

# Create module logger
log = create_module_logger(module_name=__name__)
Expand Down Expand Up @@ -104,8 +105,10 @@ def initialize_link_mixin(self):
for name, link in self.obj.links.items():
if self.metalink_prefix in name or (self._default_link is not None and link.name == self._default_link.name):
self._links[name] = link
assert np.allclose(link.scale, self.obj.scale), \
f"the meta link {name} has a inconsistent scale with the object {self.obj.name}"
# Make sure the scale is similar if the link is not a cloth prim
if not isinstance(link, ClothPrim):
assert np.allclose(link.scale, self.obj.scale), \
f"the meta link {name} has a inconsistent scale with the object {self.obj.name}"

@classproperty
def _do_not_register_classes(cls):
Expand Down
24 changes: 14 additions & 10 deletions omnigibson/objects/dataset_object.py
Original file line number Diff line number Diff line change
Expand Up @@ -231,17 +231,21 @@ def _post_load(self):
for material in self.materials:
material.shader_update_asset_paths_with_root_path(root_path)

# Assign realistic density and mass based on average object category spec
# Assign realistic density and mass based on average object category spec, or fall back to a default value
if self.avg_obj_dims is not None and self.avg_obj_dims["density"] is not None:
if self._prim_type == PrimType.RIGID:
for link in self._links.values():
# If not a meta (virtual) link, set the density based on avg_obj_dims and a zero mass (ignored)
if link.has_collision_meshes:
link.mass = 0.0
link.density = self.avg_obj_dims["density"]

elif self._prim_type == PrimType.CLOTH:
self.root_link.mass = self.avg_obj_dims["density"] * self.root_link.volume
density = self.avg_obj_dims["density"]
else:
density = 1000.0

if self._prim_type == PrimType.RIGID:
for link in self._links.values():
# If not a meta (virtual) link, set the density based on avg_obj_dims and a zero mass (ignored)
if link.has_collision_meshes:
link.mass = 0.0
link.density = density

elif self._prim_type == PrimType.CLOTH:
self.root_link.mass = density * self.root_link.volume

def _update_texture_change(self, object_state):
"""
Expand Down
3 changes: 1 addition & 2 deletions omnigibson/objects/usd_object.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,13 +94,12 @@ def _load(self):
if self._encrypted:
# Create a temporary file to store the decrytped asset, load it, and then delete it
encrypted_filename = self._usd_path.replace(".usd", ".encrypted.usd")
decrypted_fd, usd_path = tempfile.mkstemp(os.path.basename(self._usd_path), dir=og.tempdir)
usd_path = self._usd_path.replace(".usd", f".{self.uuid}.usd")
decrypt_file(encrypted_filename, usd_path)

prim = add_asset_to_stage(asset_path=usd_path, prim_path=self._prim_path)

if self._encrypted:
os.close(decrypted_fd)
# On Windows, Isaac Sim won't let go of the file until the prim is removed, so we can't delete it.
if os.name == "posix":
os.remove(usd_path)
Expand Down
16 changes: 14 additions & 2 deletions omnigibson/prims/cloth_prim.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@

# Subsample cloth particle points to boost performance
m.N_CLOTH_KEYPOINTS = 1000
m.KEYPOINT_COVERAGE_THRESHOLD = 0.80
m.KEYPOINT_COVERAGE_THRESHOLD = 0.75
m.N_CLOTH_KEYFACES = 500


Expand Down Expand Up @@ -111,7 +111,7 @@ def _post_load(self):
max(min(true_aabb[1][1], keypoint_aabb[1][1]) - max(true_aabb[0][1], keypoint_aabb[0][1]), 0) * \
max(min(true_aabb[1][2], keypoint_aabb[1][2]) - max(true_aabb[0][2], keypoint_aabb[0][2]), 0)
true_vol = np.product(true_aabb[1] - true_aabb[0])
if overlap_vol / true_vol > m.KEYPOINT_COVERAGE_THRESHOLD:
if true_vol == 0.0 or overlap_vol / true_vol > m.KEYPOINT_COVERAGE_THRESHOLD:
success = True
break
assert success, f"Did not adequately subsample keypoints for cloth {self.name}!"
Expand All @@ -131,6 +131,18 @@ def _initialize(self):
# Store the default position of the points in the local frame
self._default_positions = np.array(self.get_attribute(attr="points"))

@property
def visual_aabb(self):
return self.aabb

@property
def visual_aabb_extent(self):
return self.aabb_extent

@property
def visual_aabb_center(self):
return self.aabb_center

@classproperty
def cloth_system(cls):
return get_system("cloth")
Expand Down
3 changes: 2 additions & 1 deletion omnigibson/prims/entity_prim.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
m = create_module_macros(module_path=__file__)

# Default sleep threshold for all objects -- see https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/simulation-control/physics-settings.html?highlight=sleep#sleeping
m.DEFAULT_SLEEP_THRESHOLD = 0.005
m.DEFAULT_SLEEP_THRESHOLD = 0.001


class EntityPrim(XFormPrim):
Expand Down Expand Up @@ -1415,6 +1415,7 @@ def create_attachment_point_link(self):
link.visible = False
# Set a very small mass
link.mass = 1e-6
link.density = 0.0

self._links[link_name] = link

Expand Down
15 changes: 7 additions & 8 deletions omnigibson/prims/rigid_prim.py
Original file line number Diff line number Diff line change
Expand Up @@ -465,16 +465,15 @@ def density(self):
Returns:
float: density of the rigid body in kg / m^3.
"""
raw_usd_mass = self._rigid_prim_view.get_masses()[0]
# We first check if the raw usd mass is specified, since mass overrides density
# If it's specified, we infer density based on that value divided by volume
# Otherwise, we try to directly grab the raw usd density value, and if that value
# does not exist, we return 1000 since that is the canonical density assigned by omniverse
if raw_usd_mass != 0:
density = raw_usd_mass / self.volume
mass = self._rigid_prim_view.get_masses()[0]
# We first check if the mass is specified, since mass overrides density. If so, density = mass / volume.
# Otherwise, we try to directly grab the raw usd density value, and if that value does not exist,
# we return 1000 since that is the canonical density assigned by omniverse
if mass != 0.0:
density = mass / self.volume
else:
density = self._rigid_prim_view.get_densities()[0]
if density == 0:
if density == 0.0:
density = 1000.0

return density
Expand Down
5 changes: 3 additions & 2 deletions omnigibson/scenes/scene_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,14 @@
from omnigibson.macros import create_module_macros, gm
from omnigibson.prims.xform_prim import XFormPrim
from omnigibson.prims.material_prim import MaterialPrim
from omnigibson.utils.constants import STRUCTURE_CATEGORIES
from omnigibson.utils.python_utils import classproperty, Serializable, Registerable, Recreatable, \
create_object_from_init_info
from omnigibson.utils.registry_utils import SerializableRegistry
from omnigibson.utils.ui_utils import create_module_logger
from omnigibson.utils.usd_utils import CollisionAPI
from omnigibson.objects.object_base import BaseObject
from omnigibson.objects.dataset_object import DatasetObject
from omnigibson.systems.system_base import SYSTEM_REGISTRY, clear_all_systems, get_system
from omnigibson.objects.light_object import LightObject
from omnigibson.robots.robot_base import m as robot_macros
Expand Down Expand Up @@ -441,10 +443,9 @@ def add_object(self, obj, register=True, _is_call_from_simulator=False):
# If this object is fixed and is NOT an agent, disable collisions between the fixed links of the fixed objects
# This is to account for cases such as Tiago, which has a fixed base which is needed for its global base joints
# We do this by adding the object to our tracked collision groups
structure_categories = {"walls", "floors", "ceilings"}
if obj.fixed_base and obj.category != robot_macros.ROBOT_CATEGORY and not obj.visual_only:
# TODO: Remove structure hotfix once asset collision meshes are fixed!!
if obj.category in structure_categories:
if obj.category in STRUCTURE_CATEGORIES:
CollisionAPI.add_to_collision_group(col_group="structures", prim_path=obj.prim_path)
else:
for link in obj.links.values():
Expand Down
16 changes: 11 additions & 5 deletions omnigibson/systems/macro_particle_system.py
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,9 @@ def process_particle_object(cls):
"""
# Update color if the particle object has any material
color = np.ones(3)
if cls.particle_object.has_material():
if cls.particle_object.material.is_glass:
color = cls.particle_object.material.glass_color
else:
diffuse_texture = cls.particle_object.material.diffuse_texture
color = plt.imread(diffuse_texture).mean(axis=(0, 1)) if diffuse_texture else cls.particle_object.material.diffuse_color_constant
cls._color = color
Expand Down Expand Up @@ -355,6 +357,7 @@ class MacroVisualParticleSystem(MacroParticleSystem, VisualParticleSystem):
_SAMPLING_BIMODAL_MEAN_FRACTION = 0.9
_SAMPLING_BIMODAL_STDEV_FRACTION = 0.2
_SAMPLING_MAX_ATTEMPTS = 20
_SAMPLING_HIT_PROPORTION = 0.4

@classmethod
def initialize(cls):
Expand Down Expand Up @@ -571,6 +574,7 @@ def generate_group_particles_on_object(cls, group, max_samples, min_samples_for_
aabb_offset=cls._SAMPLING_AABB_OFFSET,
max_sampling_attempts=cls._SAMPLING_MAX_ATTEMPTS,
refuse_downwards=True,
hit_proportion=cls._SAMPLING_HIT_PROPORTION,
)

# Use sampled points
Expand Down Expand Up @@ -693,8 +697,10 @@ def _modify_batch_particles_position_orientation(cls, particles, positions=None,
Modifies all @particles' positions and orientations with @positions and @orientations
Args:
particles (Iterable of str): Names of particles to compute batched position orientation for
local (bool): Whether to set particles' poses in local frame or not
particles (Iterable of str): Names of particles to modify
positions (None or (n, 3)-array): New positions to set for the particles
orientations (None or (n, 4)-array): New orientations to set for the particles
local (bool): Whether to modify particles' poses in local frame or not
Returns:
2-tuple:
Expand All @@ -712,15 +718,15 @@ def _modify_batch_particles_position_orientation(cls, particles, positions=None,
lens = np.array([len(particles), len(positions), len(orientations)])
assert lens.min() == lens.max(), "Got mismatched particles, positions, and orientations!"

particle_local_poses_batch = np.zeros((cls.n_particles, 4, 4))
particle_local_poses_batch = np.zeros((n_particles, 4, 4))
particle_local_poses_batch[:, -1, -1] = 1.0
particle_local_poses_batch[:, :3, 3] = positions
particle_local_poses_batch[:, :3, :3] = T.quat2mat(orientations)

if not local:
# Iterate over all particles and compute link tfs programmatically, then batch the matrix transform
link_tfs = dict()
link_tfs_batch = np.zeros((cls.n_particles, 4, 4))
link_tfs_batch = np.zeros((n_particles, 4, 4))
for i, name in enumerate(particles):
obj = cls._particles_info[name]["obj"]
is_cloth = cls._is_cloth_obj(obj=obj)
Expand Down
Loading

0 comments on commit 8105c2a

Please sign in to comment.