Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Profiling #139

Merged
merged 5 commits into from
Feb 13, 2024
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
53 changes: 53 additions & 0 deletions .github/workflows/profiling.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
name: Profiling

on:
push:
branches:
- og-develop

permissions:
# deployments permission to deploy GitHub pages website
deployments: write
# contents permission to update profiling contents in gh-pages branch
contents: write

concurrency:
group: ${{ github.workflow }}-${{ github.event_name == 'pull_request' && github.head_ref || github.sha }}
cancel-in-progress: true

jobs:
profiling:
name: Speed Profiling
runs-on: [self-hosted, linux, gpu, dataset-enabled]

defaults:
run:
shell: micromamba run -n omnigibson /bin/bash -leo pipefail {0}

steps:
- name: Fix home
run: echo "HOME=/root" >> $GITHUB_ENV

- name: Checkout source
uses: actions/checkout@v3

- name: Install dev requirements
run: pip install -r requirements-dev.txt

- name: Install
run: pip install -e .

- name: Run performance benchmark
run: bash scripts/profiling.sh

- name: Store benchmark result
uses: benchmark-action/github-action-benchmark@v1
with:
tool: 'customSmallerIsBetter'
output-file-path: output.json
benchmark-data-dir-path: profiling
fail-on-alert: false
alert-threshold: '200%'
github-token: ${{ secrets.GITHUB_TOKEN }}
comment-on-alert: true
auto-push: true
3 changes: 3 additions & 0 deletions omnigibson/macros.py
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,9 @@
# CANNOT be set at runtime
gm.GUI_VIEWPORT_ONLY = False

# Whether to use the viewer camera or not
gm.RENDER_VIEWER_CAMERA = True

# Do not suppress known omni warnings / errors, and also put omnigibson in a debug state
# This includes extra information for things such as object sampling, and also any debug
# logging messages
Expand Down
30 changes: 13 additions & 17 deletions omnigibson/objects/object_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,7 @@
import omnigibson as og
import omnigibson.lazy as lazy
from omnigibson.macros import create_module_macros, gm
from omnigibson.utils.constants import (
DEFAULT_COLLISION_GROUP,
SPECIAL_COLLISION_GROUPS,
SemanticClass,
)
from omnigibson.utils.constants import SemanticClass
from omnigibson.utils.usd_utils import create_joint, CollisionAPI
from omnigibson.prims.entity_prim import EntityPrim
from omnigibson.utils.python_utils import Registerable, classproperty, get_uuid
Expand Down Expand Up @@ -88,10 +84,6 @@ def __init__(
self.category = category
self.fixed_base = fixed_base

# This sets the collision group of the object. In omnigibson, objects are only permitted to be part of a single
# collision group, e.g. collisions are only enabled within a single group
self.collision_group = SPECIAL_COLLISION_GROUPS.get(self.category, DEFAULT_COLLISION_GROUP)

# Infer class ID if not specified
if class_id is None:
class_id = CLASS_NAME_TO_CLASS_ID.get(category, SemanticClass.USER_ADDED_OBJS)
Expand Down Expand Up @@ -177,25 +169,29 @@ def _post_load(self):
if "visible" in self._load_config and self._load_config["visible"] is not None:
self.visible = self._load_config["visible"]

# First, remove any articulation root API that already exists at the object-level prim
# First, remove any articulation root API that already exists at the object-level or root link level prim
if self._prim.HasAPI(lazy.pxr.UsdPhysics.ArticulationRootAPI):
self._prim.RemoveAPI(lazy.pxr.UsdPhysics.ArticulationRootAPI)
self._prim.RemoveAPI(lazy.pxr.PhysxSchema.PhysxArticulationAPI)

if self.root_prim.HasAPI(lazy.pxr.UsdPhysics.ArticulationRootAPI):
self.root_prim.RemoveAPI(lazy.pxr.UsdPhysics.ArticulationRootAPI)
self.root_prim.RemoveAPI(lazy.pxr.PhysxSchema.PhysxArticulationAPI)

# Potentially add articulation root APIs and also set self collisions
root_prim = None if self.articulation_root_path is None else lazy.omni.isaac.core.utils.prims.get_prim_at_path(self.articulation_root_path)
if root_prim is not None:
lazy.pxr.UsdPhysics.ArticulationRootAPI.Apply(root_prim)
lazy.pxr.PhysxSchema.PhysxArticulationAPI.Apply(root_prim)
self.self_collisions = self._load_config["self_collisions"]

# TODO: Do we need to explicitly add all links? or is adding articulation root itself sufficient?
# Set the collision group
CollisionAPI.add_to_collision_group(
col_group=self.collision_group,
prim_path=self.prim_path,
create_if_not_exist=True,
)
# Set the collision group if needed
# We always filter collision groups between structures and fixed objects
if self.fixed_base:
CollisionAPI.add_to_collision_group(
col_group="fixed_base",
prim_path=self.prim_path,
)

# Update semantics
lazy.omni.isaac.core.utils.semantics.add_update_semantics(
Expand Down
68 changes: 42 additions & 26 deletions omnigibson/prims/entity_prim.py
Original file line number Diff line number Diff line change
Expand Up @@ -897,44 +897,60 @@ def get_relative_angular_velocity(self):
return T.quat2mat(self.get_orientation()).T @ self.get_angular_velocity()

def set_position_orientation(self, position=None, orientation=None):
# If kinematic only, clear cache for the root link
if self.kinematic_only:
self.root_link.clear_kinematic_only_cache()
if og.sim.is_stopped():
return XFormPrim.set_position_orientation(self, position, orientation)
wensi-ai marked this conversation as resolved.
Show resolved Hide resolved
# Delegate to RigidPrim if we are not articulated
if self._articulation_view is None:
return self.root_link.set_position_orientation(position=position, orientation=orientation)

if position is not None:
position = np.asarray(position)[None, :]
if orientation is not None:
orientation = np.asarray(orientation)[None, [3, 0, 1, 2]]
self._articulation_view.set_world_poses(position, orientation)
BoundingBoxAPI.clear()
if og.sim.is_stopped():
XFormPrim.set_position_orientation(self, position=position, orientation=orientation)
elif self._articulation_view is None:
self.root_link.set_position_orientation(position=position, orientation=orientation)
else:
if position is not None:
position = np.asarray(position)[None, :]
if orientation is not None:
orientation = np.asarray(orientation)[None, [3, 0, 1, 2]]
self._articulation_view.set_world_poses(position, orientation)
BoundingBoxAPI.clear()

def get_position_orientation(self):
if og.sim.is_stopped():
return XFormPrim.get_position_orientation(self)
# Delegate to RigidPrim if we are not articulated
if self._articulation_view is None:
elif self._articulation_view is None:
return self.root_link.get_position_orientation()

positions, orientations = self._articulation_view.get_world_poses()
return positions[0], orientations[0][[1, 2, 3, 0]]
else:
positions, orientations = self._articulation_view.get_world_poses()
return positions[0], orientations[0][[1, 2, 3, 0]]

def set_local_pose(self, position=None, orientation=None):
# If kinematic only, clear cache for the root link
if self.kinematic_only:
self.root_link.clear_kinematic_only_cache()
if og.sim.is_stopped():
return XFormPrim.set_local_pose(self, position, orientation)
# Delegate to RigidPrim if we are not articulated
if self._articulation_view is None:
return self.root_link.set_local_pose(position=position, orientation=orientation)

if position is not None:
position = np.asarray(position)[None, :]
if orientation is not None:
orientation = np.asarray(orientation)[None, [3, 0, 1, 2]]
self._articulation_view.set_local_poses(position, orientation)
BoundingBoxAPI.clear()
elif self._articulation_view is None:
self.root_link.set_local_pose(position=position, orientation=orientation)
else:
if position is not None:
position = np.asarray(position)[None, :]
if orientation is not None:
orientation = np.asarray(orientation)[None, [3, 0, 1, 2]]
self._articulation_view.set_local_poses(position, orientation)
BoundingBoxAPI.clear()

def get_local_pose(self):
if og.sim.is_stopped():
return XFormPrim.get_local_pose(self)
# Delegate to RigidPrim if we are not articulated
if self._articulation_view is None:
elif self._articulation_view is None:
return self.root_link.get_local_pose()

positions, orientations = self._articulation_view.get_local_poses()
return positions[0], orientations[0][[1, 2, 3, 0]]
else:
positions, orientations = self._articulation_view.get_local_poses()
return positions[0], orientations[0][[1, 2, 3, 0]]

# TODO: Is the omni joint damping (used for driving motors) same as dissipative joint damping (what we had in pb)?
@property
Expand Down
15 changes: 11 additions & 4 deletions omnigibson/prims/rigid_prim.py
Original file line number Diff line number Diff line change
Expand Up @@ -291,8 +291,7 @@ def get_angular_velocity(self):
def set_position_orientation(self, position=None, orientation=None):
# Invalidate kinematic-only object pose caches when new pose is set
if self.kinematic_only:
self._kinematic_world_pose_cache = None
self._kinematic_local_pose_cache = None
self.clear_kinematic_only_cache()
if position is not None:
position = np.asarray(position)[None, :]
if orientation is not None:
Expand Down Expand Up @@ -321,8 +320,7 @@ def get_position_orientation(self):
def set_local_pose(self, position=None, orientation=None):
# Invalidate kinematic-only object pose caches when new pose is set
if self.kinematic_only:
self._kinematic_world_pose_cache = None
self._kinematic_local_pose_cache = None
self.clear_kinematic_only_cache()
if position is not None:
position = np.asarray(position)[None, :]
if orientation is not None:
Expand Down Expand Up @@ -622,6 +620,15 @@ def sleep(self):
prim_id = lazy.pxr.PhysicsSchemaTools.sdfPathToInt(self.prim_path)
og.sim.psi.put_to_sleep(og.sim.stage_id, prim_id)

def clear_kinematic_only_cache(self):
"""
Clears the internal kinematic only cached pose. Useful if the parent prim's pose
changes without explicitly calling this prim's pose setter
"""
assert self.kinematic_only
self._kinematic_local_pose_cache = None
self._kinematic_world_pose_cache = None

def _dump_state(self):
# Grab pose from super class
state = super()._dump_state()
Expand Down
20 changes: 3 additions & 17 deletions omnigibson/scenes/scene_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
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.systems.system_base import SYSTEM_REGISTRY, clear_all_systems, get_system
from omnigibson.objects.light_object import LightObject
Expand Down Expand Up @@ -170,6 +171,8 @@ def _load(self):
Load the scene into simulator
The elements to load may include: floor, building, objects, etc.
"""
# Add collision group for fixed objects
CollisionAPI.create_collision_group(col_group="fixed_base", filter_self_collisions=True)
# We just add a ground plane if requested
if self._use_floor_plane:
self.add_ground_plane(color=self._floor_plane_color, visible=self._floor_plane_visible)
Expand Down Expand Up @@ -424,23 +427,6 @@ def add_object(self, obj, register=True, _is_call_from_simulator=False):
# let scene._load() load the object when called later on.
prim = obj.load()

# 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
if obj.fixed_base and obj.category != robot_macros.ROBOT_CATEGORY:
# TODO: Remove building hotfix once asset collision meshes are fixed!!
building_categories = {"walls", "floors", "ceilings"}
for fixed_obj in self.fixed_objects.values():
# Filter out collisions between walls / ceilings / floors and ALL links of the other object
if obj.category in building_categories:
for link in fixed_obj.links.values():
obj.root_link.add_filtered_collision_pair(link)
elif fixed_obj.category in building_categories:
for link in obj.links.values():
fixed_obj.root_link.add_filtered_collision_pair(link)
else:
# Only filter out root links
obj.root_link.add_filtered_collision_pair(fixed_obj.root_link)

# Add this object to our registry based on its type, if we want to register it
if register:
self.object_registry.add(obj)
Expand Down
1 change: 1 addition & 0 deletions omnigibson/simulator.py
Original file line number Diff line number Diff line change
Expand Up @@ -1269,6 +1269,7 @@ def _init_stage(
position=np.array(m.DEFAULT_VIEWER_CAMERA_POS),
orientation=np.array(m.DEFAULT_VIEWER_CAMERA_QUAT),
)
self.viewer_visibility = gm.RENDER_VIEWER_CAMERA

def close(self):
"""
Expand Down
9 changes: 0 additions & 9 deletions omnigibson/utils/constants.py
Original file line number Diff line number Diff line change
Expand Up @@ -69,15 +69,6 @@ class ParticleModifyCondition(str, Enum):
# Structure categories that need to always be loaded for stability purposes
STRUCTURE_CATEGORIES = frozenset({"floors", "walls", "ceilings", "lawn", "driveway", "fence"})

# Note that we are starting this from bit 6 since bullet seems to be giving special meaning to groups 0-5.
# Collision groups for objects. For special logic, different categories can be assigned different collision groups.
ALL_COLLISION_GROUPS_MASK = -1
DEFAULT_COLLISION_GROUP = "default"
SPECIAL_COLLISION_GROUPS = {
"floors": "floors",
"carpet": "carpet",
}


# Joint friction magic values to assign to objects based on their category
DEFAULT_JOINT_FRICTION = 10.0
Expand Down
80 changes: 80 additions & 0 deletions omnigibson/utils/profiling_utils.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
import gym
import omnigibson as og
import os
import psutil
from pynvml.smi import nvidia_smi
from time import time


class ProfilingEnv(og.Environment):
def step(self, action):
try:
start = time()
# If the action is not a dictionary, convert into a dictionary
if not isinstance(action, dict) and not isinstance(action, gym.spaces.Dict):
action_dict = dict()
idx = 0
for robot in self.robots:
action_dim = robot.action_dim
action_dict[robot.name] = action[idx: idx + action_dim]
idx += action_dim
else:
# Our inputted action is the action dictionary
action_dict = action

# Iterate over all robots and apply actions
for robot in self.robots:
robot.apply_action(action_dict[robot.name])

# Run simulation step
sim_start = time()
if len(og.sim._objects_to_initialize) > 0:
og.sim.render()
super(type(og.sim), og.sim).step(render=True)
omni_time = (time() - sim_start) * 1e3

# Additionally run non physics things
og.sim._non_physics_step()

# Grab observations
obs = self.get_obs()

# Step the scene graph builder if necessary
if self._scene_graph_builder is not None:
self._scene_graph_builder.step(self.scene)

# Grab reward, done, and info, and populate with internal info
reward, done, info = self.task.step(self, action)
self._populate_info(info)

if done and self._automatic_reset:
# Add lost observation to our information dict, and reset
info["last_observation"] = obs
obs = self.reset()

# Increment step
self._current_step += 1

# collect profiling data
total_frame_time = (time() - start) * 1e3
og_time = total_frame_time - omni_time
# memory usage in GB
memory_usage = psutil.Process(os.getpid()).memory_info().rss / 1024 ** 3
# VRAM usage in GB
for gpu in nvidia_smi.getInstance().DeviceQuery()['gpu']:
found = False
for process in gpu['processes']:
if process['pid'] == os.getpid():
vram_usage = process['used_memory'] / 1024
found = True
break
if found:
break

ret = [total_frame_time, omni_time, og_time, memory_usage, vram_usage]
if self._current_step % 100 == 0:
print("total time: {:.3f} ms, Omni time: {:.3f} ms, OG time: {:.3f} ms, memory: {:.3f} GB, vram: {:.3f} GB.".format(*ret))

return obs, reward, done, info, ret
except:
raise ValueError(f"Failed to execute environment step {self._current_step} in episode {self._current_episode}")
Loading
Loading