Unverified Commit 3f2beaf5 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Fixes unit tests of existing features (#134)

# Description

This PR checks that all the existing scripts in the codebase work as
expected. The last few merges led to the deletion of some files that
were no longer available to import in the unit tests. Also renamed files
in the test to follow the following convention:

* `test_*.py` : A script that tests a feature using unittest fixture
* `check_*.py`: A script that runs the feature but doesn't necessarily
put them as a unittest fixture.

## Type of change

- Bug fix (non-breaking change which fixes an issue)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
parent 8c5a0697
......@@ -21,7 +21,6 @@ omni.isaac.orbit extension
orbit.command_generators
orbit.utils
orbit.utils.assets
orbit.utils.kit
orbit.utils.math
orbit.utils.mdp
orbit.compat
......
......@@ -8,7 +8,8 @@ omni.isaac.orbit.compat
* :mod:`omni.isaac.orbit.markers`
* :mod:`omni.isaac.orbit.sensors`
* :mod:`omni.isaac.orbit.utils.mdp`
* :mod:`omni.isaac.orbit.managers`
* :mod:`omni.isaac.orbit.sim`
Markers
-------
......@@ -103,3 +104,11 @@ MDP Managers
:members:
:undoc-members:
:show-inheritance:
Kit Utilities
-------------
.. automodule:: omni.isaac.orbit.compat.utils.kit
:members:
:undoc-members:
:show-inheritance:
omni.isaac.orbit.utils.kit
==========================
.. automodule:: omni.isaac.orbit.utils.kit
:members:
:undoc-members:
:show-inheritance:
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.9.2"
version = "0.9.3"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.9.3 (2023-08-23)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Enabled the `faulthander <https://docs.python.org/3/library/faulthandler.html>`_ to catch segfaults and print
the stack trace. This is enabled by default in the :class:`omni.isaac.orbit.app.AppLauncher` class.
Fixed
^^^^^
* Re-added the :mod:`omni.isaac.orbit.utils.kit` to the ``compat`` directory and fixed all the references to it.
* Fixed the deletion of Replicator nodes for the :class:`omni.isaac.orbit.sensors.Camera` class. Earlier, the
Replicator nodes were not being deleted when the camera was deleted. However, this does not prevent the random
crashes that happen when the camera is deleted.
* Fixed the :meth:`omni.isaac.orbit.utils.math.convert_quat` to support both numpy and torch tensors.
Changed
^^^^^^^
* Renamed all the scripts inside the ``test`` directory to follow the convention:
* ``test_<module_name>.py``: Tests for the module ``<module_name>`` using unittest.
* ``check_<module_name>``: Check for the module ``<module_name>`` using python main function.
0.9.2 (2023-08-22)
~~~~~~~~~~~~~~~~~~~
......
......@@ -72,6 +72,7 @@ Alternatively, one can set the environment variables to the python script direct
"""
import faulthandler
import os
import re
import sys
......@@ -135,6 +136,9 @@ class AppLauncher:
.. _SimulationApp: https://docs.omniverse.nvidia.com/py/isaacsim/source/extensions/omni.isaac.kit/docs/index.html
.. _documentation: https://docs.omniverse.nvidia.com/py/isaacsim/source/extensions/omni.isaac.kit/docs/index.html
"""
# Enable call-stack on crash
faulthandler.enable()
# Headless is always true for remote deployment
remote_deployment = int(os.environ.get("REMOTE_DEPLOYMENT", 0))
# resolve headless execution of simulation app
......
......@@ -15,7 +15,7 @@ from omni.isaac.core.materials import PreviewSurface
from omni.isaac.core.prims import GeometryPrim
from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR, check_file_path
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
import contextlib
import math
from typing import Optional, Sequence
import carb
import omni.isaac.core.utils.nucleus as nucleus_utils
import omni.isaac.core.utils.prims as prim_utils
import omni.kit
from omni.isaac.core.materials import PhysicsMaterial
from omni.isaac.core.prims import GeometryPrim
from pxr import Gf, PhysxSchema, UsdPhysics, UsdShade
def create_ground_plane(
prim_path: str,
z_position: float = 0.0,
static_friction: float = 1.0,
dynamic_friction: float = 1.0,
restitution: float = 0.0,
color: Optional[Sequence[float]] = (0.065, 0.0725, 0.080),
**kwargs,
):
"""Spawns a ground plane into the scene.
This method spawns the default ground plane (grid plane) from Isaac Sim into the scene.
It applies a physics material to the ground plane and sets the color of the ground plane.
Args:
prim_path (str): The prim path to spawn the ground plane at.
z_position (float, optional): The z-location of the plane. Defaults to 0.
static_friction (float, optional): The static friction coefficient. Defaults to 1.0.
dynamic_friction (float, optional): The dynamic friction coefficient. Defaults to 1.0.
restitution (float, optional): The coefficient of restitution. Defaults to 0.0.
color (Optional[Sequence[float]], optional): The color of the ground plane.
Defaults to (0.065, 0.0725, 0.080).
Keyword Args:
usd_path (str): The USD path to the ground plane. Defaults to the asset path
`Isaac/Environments/Grid/default_environment.usd` on the Isaac Sim Nucleus server.
improve_patch_friction (bool): Whether to enable patch friction. Defaults to False.
combine_mode (str): Determines the way physics materials will be combined during collisions.
Available options are `average`, `min`, `multiply`, `multiply`, and `max`. Defaults to `average`.
light_intensity (Optional[float]): The power intensity of the light source. Defaults to 1e7.
light_radius (Optional[float]): The radius of the light source. Defaults to 50.0.
"""
# Retrieve path to the plane
if "usd_path" in kwargs:
usd_path = kwargs["usd_path"]
else:
# get path to the nucleus server
assets_root_path = nucleus_utils.get_assets_root_path()
if assets_root_path is None:
carb.log_error("Unable to access the Isaac Sim assets folder on Nucleus server.")
return
# prepend path to the grid plane
usd_path = f"{assets_root_path}/Isaac/Environments/Grid/default_environment.usd"
# Spawn Ground-plane
prim_utils.create_prim(prim_path, usd_path=usd_path, translation=(0.0, 0.0, z_position))
# Create physics material
material = PhysicsMaterial(
f"{prim_path}/groundMaterial",
static_friction=static_friction,
dynamic_friction=dynamic_friction,
restitution=restitution,
)
# Apply PhysX Rigid Material schema
physx_material_api = PhysxSchema.PhysxMaterialAPI.Apply(material.prim)
# Set patch friction property
improve_patch_friction = kwargs.get("improve_patch_friction", False)
physx_material_api.CreateImprovePatchFrictionAttr().Set(improve_patch_friction)
# Set combination mode for coefficients
combine_mode = kwargs.get("friciton_combine_mode", "multiply")
physx_material_api.CreateFrictionCombineModeAttr().Set(combine_mode)
physx_material_api.CreateRestitutionCombineModeAttr().Set(combine_mode)
# Apply physics material to ground plane
collision_prim_path = prim_utils.get_prim_path(
prim_utils.get_first_matching_child_prim(
prim_path, predicate=lambda x: prim_utils.get_prim_type_name(x) == "Plane"
)
)
geom_prim = GeometryPrim(collision_prim_path, disable_stablization=False, collision=True)
geom_prim.apply_physics_material(material)
# Change the color of the plane
# Warning: This is specific to the default grid plane asset.
if color is not None:
omni.kit.commands.execute(
"ChangeProperty",
prop_path=f"{prim_path}/Looks/theGrid.inputs:diffuse_tint",
value=Gf.Vec3f(*color),
prev=None,
)
# Change the settings of the sphere light
# By default, the one from Isaac Sim is too dim for large number of environments.
# Warning: This is specific to the default grid plane asset.
light_intensity = kwargs.get("light_intensity", 1e7)
light_radius = kwargs.get("light_radius", 100.0)
# -- light intensity
if light_intensity is not None:
omni.kit.commands.execute(
"ChangeProperty",
prop_path=f"{prim_path}/SphereLight.intensity",
value=light_intensity,
prev=None,
)
# -- light radius
if light_radius is not None:
# set radius of the light
omni.kit.commands.execute(
"ChangeProperty",
prop_path=f"{prim_path}/SphereLight.radius",
value=light_radius,
prev=None,
)
# as a rule of thumb, we set the sphere center 1.5 times
omni.kit.commands.execute(
"ChangeProperty",
prop_path=f"{prim_path}/SphereLight.xformOp:translate",
value=(0.0, 0.0, 1.5 * light_radius),
prev=None,
)
# -- ambient light
ambient_light = kwargs.get("ambient_light", True)
if ambient_light:
prim_utils.create_prim(
f"{prim_path}/AmbientLight",
"DistantLight",
attributes={"intensity": 600.0},
)
def move_nested_prims(source_ns: str, target_ns: str):
"""Moves all prims from source namespace to target namespace.
This function also moves all the references inside the source prim path
to the target prim path.
Args:
source_ns (str): The source prim path.
target_ns (str): The target prim path.
"""
# check if target namespace exists
prim_utils.define_prim(target_ns)
# move all children prim from source namespace
prim = prim_utils.get_prim_at_path(source_ns)
for children in prim.GetChildren():
orig_prim_path = prim_utils.get_prim_path(children)
new_prim_path = orig_prim_path.replace(source_ns, target_ns)
prim_utils.move_prim(orig_prim_path, new_prim_path)
def set_drive_dof_properties(
prim_path: str,
dof_name: str,
stiffness: Optional[float] = None,
damping: Optional[float] = None,
max_velocity: Optional[float] = None,
max_force: Optional[float] = None,
) -> None:
"""Set the DOF properties of a drive on an articulation.
Args:
prim_path (str): The prim path to the articulation root.
dof_name (str): The name of the DOF/joint.
stiffness (Optional[float]): The stiffness of the drive.
damping (Optional[float]): The damping of the drive.
max_velocity (Optional[float]): The max velocity of the drive.
max_force (Optional[float]): The max effort of the drive.
Raises:
ValueError: When no joint of given name found under the provided prim path.
"""
# find matching prim path for the dof name
dof_prim = prim_utils.get_first_matching_child_prim(prim_path, lambda x: dof_name in x)
if not dof_prim.IsValid():
raise ValueError(f"No joint named '{dof_name}' found in articulation '{prim_path}'.")
# obtain the dof drive type
if dof_prim.IsA(UsdPhysics.RevoluteJoint):
drive_type = "angular"
elif dof_prim.IsA(UsdPhysics.PrismaticJoint):
drive_type = "linear"
else:
# get joint USD prim
dof_prim_path = prim_utils.get_prim_path(dof_prim)
raise ValueError(f"The joint at path '{dof_prim_path}' is not linear or angular.")
# convert to USD Physics drive
if dof_prim.HasAPI(UsdPhysics.DriveAPI):
drive_api = UsdPhysics.DriveAPI(dof_prim, drive_type)
else:
drive_api = UsdPhysics.DriveAPI.Apply(dof_prim, drive_type)
# convert DOF type to be force
if not drive_api.GetTypeAttr():
drive_api.CreateTypeAttr().Set("force")
else:
drive_api.GetTypeAttr().Set("force")
# set stiffness of the drive
if stiffness is not None:
# convert from radians to degrees
# note: gains have units "per degrees"
if drive_type == "angular":
stiffness = stiffness * math.pi / 180
# set property
if not drive_api.GetStiffnessAttr():
drive_api.CreateStiffnessAttr(stiffness)
else:
drive_api.GetStiffnessAttr().Set(stiffness)
# set damping of the drive
if damping is not None:
# convert from radians to degrees
# note: gains have units "per degrees"
if drive_type == "angular":
damping = damping * math.pi / 180
# set property
if not drive_api.GetDampingAttr():
drive_api.CreateDampingAttr(damping)
else:
drive_api.GetDampingAttr().Set(damping)
# set maximum force
if max_force is not None:
if not drive_api.GetMaxForceAttr():
drive_api.CreateMaxForceAttr(max_force)
else:
drive_api.GetMaxForceAttr().Set(max_force)
# convert to physx schema
drive_schema = PhysxSchema.PhysxJointAPI(dof_prim)
# set maximum velocity
if max_velocity is not None:
# convert from radians to degrees
if drive_type == "angular":
max_velocity = math.degrees(max_velocity)
# set property
if not drive_schema.GetMaxJointVelocityAttr():
drive_schema.CreateMaxJointVelocityAttr(max_velocity)
else:
drive_schema.GetMaxJointVelocityAttr().Set(max_velocity)
def set_articulation_properties(
prim_path: str,
articulation_enabled: Optional[bool] = None,
solver_position_iteration_count: Optional[int] = None,
solver_velocity_iteration_count: Optional[int] = None,
sleep_threshold: Optional[float] = None,
stabilization_threshold: Optional[float] = None,
enable_self_collisions: Optional[bool] = None,
) -> None:
"""Set PhysX parameters for an articulation prim.
Args:
prim_path (str): The prim path to the articulation root.
articulation_enabled (Optional[bool]): Whether the articulation should be enabled/disabled.
solver_position_iteration_count (Optional[int]): Solver position iteration counts for the body.
solver_velocity_iteration_count (Optional[int]): Solver velocity iteration counts for the body.
sleep_threshold (Optional[float]): Mass-normalized kinetic energy threshold below which an
actor may go to sleep.
stabilization_threshold (Optional[float]): The mass-normalized kinetic energy threshold below
which an articulation may participate in stabilization.
enable_self_collisions (Optional[bool]): Boolean defining whether self collisions should be
enabled or disabled.
Raises:
ValueError: When no articulation schema found at specified articulation path.
"""
# get articulation USD prim
articulation_prim = prim_utils.get_prim_at_path(prim_path)
# check if prim has articulation applied on it
if not UsdPhysics.ArticulationRootAPI(articulation_prim):
raise ValueError(f"No articulation schema present for prim '{prim_path}'.")
# retrieve the articulation api
physx_articulation_api = PhysxSchema.PhysxArticulationAPI(articulation_prim)
if not physx_articulation_api:
physx_articulation_api = PhysxSchema.PhysxArticulationAPI.Apply(articulation_prim)
# set enable/disable rigid body API
if articulation_enabled is not None:
physx_articulation_api.GetArticulationEnabledAttr().Set(articulation_enabled)
# set solver position iteration
if solver_position_iteration_count is not None:
physx_articulation_api.GetSolverPositionIterationCountAttr().Set(solver_position_iteration_count)
# set solver velocity iteration
if solver_velocity_iteration_count is not None:
physx_articulation_api.GetSolverVelocityIterationCountAttr().Set(solver_velocity_iteration_count)
# set sleep threshold
if sleep_threshold is not None:
physx_articulation_api.GetSleepThresholdAttr().Set(sleep_threshold)
# set stabilization threshold
if stabilization_threshold is not None:
physx_articulation_api.GetStabilizationThresholdAttr().Set(stabilization_threshold)
# set self collisions
if enable_self_collisions is not None:
physx_articulation_api.GetEnabledSelfCollisionsAttr().Set(enable_self_collisions)
def set_rigid_body_properties(
prim_path: str,
rigid_body_enabled: Optional[bool] = None,
solver_position_iteration_count: Optional[int] = None,
solver_velocity_iteration_count: Optional[int] = None,
linear_damping: Optional[float] = None,
angular_damping: Optional[float] = None,
max_linear_velocity: Optional[float] = None,
max_angular_velocity: Optional[float] = None,
sleep_threshold: Optional[float] = None,
stabilization_threshold: Optional[float] = None,
max_depenetration_velocity: Optional[float] = None,
max_contact_impulse: Optional[float] = None,
enable_gyroscopic_forces: Optional[bool] = None,
disable_gravity: Optional[bool] = None,
retain_accelerations: Optional[bool] = None,
):
"""Set PhysX parameters for a rigid body prim.
Args:
prim_path (str): The prim path to the rigid body.
rigid_body_enabled (Optional[bool]): Whether to enable or disable rigid body API.
solver_position_iteration_count (Optional[int]): Solver position iteration counts for the body.
solver_velocity_iteration_count (Optional[int]): Solver velocity iteration counts for the body.
linear_damping (Optional[float]): Linear damping coefficient.
angular_damping (Optional[float]): Angular damping coefficient.
max_linear_velocity (Optional[float]): Max allowable linear velocity for rigid body (in m/s).
max_angular_velocity (Optional[float]): Max allowable angular velocity for rigid body (in rad/s).
sleep_threshold (Optional[float]): Mass-normalized kinetic energy threshold below which an actor
may go to sleep.
stabilization_threshold (Optional[float]): Mass-normalized kinetic energy threshold below which
an actor may participate in stabilization.
max_depenetration_velocity (Optional[float]): The maximum depenetration velocity permitted to
be introduced by the solver (in m/s).
max_contact_impulse (Optional[float]): The limit on the impulse that may be applied at a contact.
enable_gyroscopic_forces (Optional[bool]): Enables computation of gyroscopic forces on the
rigid body.
disable_gravity (Optional[bool]): Disable gravity for the actor.
retain_accelerations (Optional[bool]): Carries over forces/accelerations over sub-steps.
Raises:
ValueError: When no rigid-body schema found at specified prim path.
"""
# get rigid-body USD prim
rigid_body_prim = prim_utils.get_prim_at_path(prim_path)
# check if prim has rigid-body applied on it
if not UsdPhysics.RigidBodyAPI(rigid_body_prim):
raise ValueError(f"No rigid body schema present for prim '{prim_path}'.")
# retrieve the USD rigid-body api
usd_rigid_body_api = UsdPhysics.RigidBodyAPI(rigid_body_prim)
# retrieve the physx rigid-body api
physx_rigid_body_api = PhysxSchema.PhysxRigidBodyAPI(rigid_body_prim)
if not physx_rigid_body_api:
physx_rigid_body_api = PhysxSchema.PhysxRigidBodyAPI.Apply(rigid_body_prim)
# set enable/disable rigid body API
if rigid_body_enabled is not None:
usd_rigid_body_api.GetRigidBodyEnabledAttr().Set(rigid_body_enabled)
# set solver position iteration
if solver_position_iteration_count is not None:
physx_rigid_body_api.GetSolverPositionIterationCountAttr().Set(solver_position_iteration_count)
# set solver velocity iteration
if solver_velocity_iteration_count is not None:
physx_rigid_body_api.GetSolverVelocityIterationCountAttr().Set(solver_velocity_iteration_count)
# set linear damping
if linear_damping is not None:
physx_rigid_body_api.GetLinearDampingAttr().Set(linear_damping)
# set angular damping
if angular_damping is not None:
physx_rigid_body_api.GetAngularDampingAttr().Set(angular_damping)
# set max linear velocity
if max_linear_velocity is not None:
physx_rigid_body_api.GetMaxLinearVelocityAttr().Set(max_linear_velocity)
# set max angular velocity
if max_angular_velocity is not None:
max_angular_velocity = math.degrees(max_angular_velocity)
physx_rigid_body_api.GetMaxAngularVelocityAttr().Set(max_angular_velocity)
# set sleep threshold
if sleep_threshold is not None:
physx_rigid_body_api.GetSleepThresholdAttr().Set(sleep_threshold)
# set stabilization threshold
if stabilization_threshold is not None:
physx_rigid_body_api.GetStabilizationThresholdAttr().Set(stabilization_threshold)
# set max depenetration velocity
if max_depenetration_velocity is not None:
physx_rigid_body_api.GetMaxDepenetrationVelocityAttr().Set(max_depenetration_velocity)
# set max contact impulse
if max_contact_impulse is not None:
physx_rigid_body_api.GetMaxContactImpulseAttr().Set(max_contact_impulse)
# set enable gyroscopic forces
if enable_gyroscopic_forces is not None:
physx_rigid_body_api.GetEnableGyroscopicForcesAttr().Set(enable_gyroscopic_forces)
# set disable gravity
if disable_gravity is not None:
physx_rigid_body_api.GetDisableGravityAttr().Set(disable_gravity)
# set retain accelerations
if retain_accelerations is not None:
physx_rigid_body_api.GetRetainAccelerationsAttr().Set(retain_accelerations)
def set_collision_properties(
prim_path: str,
collision_enabled: Optional[bool] = None,
contact_offset: Optional[float] = None,
rest_offset: Optional[float] = None,
torsional_patch_radius: Optional[float] = None,
min_torsional_patch_radius: Optional[float] = None,
):
"""Set PhysX properties of collider prim.
Args:
prim_path (str): The prim path of parent.
collision_enabled (Optional[bool], optional): Whether to enable/disable collider.
contact_offset (Optional[float], optional): Contact offset of a collision shape (in m).
rest_offset (Optional[float], optional): Rest offset of a collision shape (in m).
torsional_patch_radius (Optional[float], optional): Defines the radius of the contact patch
used to apply torsional friction (in m).
min_torsional_patch_radius (Optional[float], optional): Defines the minimum radius of the
contact patch used to apply torsional friction (in m).
Raises:
ValueError: When no collision schema found at specified prim path.
"""
# get USD prim
collider_prim = prim_utils.get_prim_at_path(prim_path)
# check if prim has collision applied on it
if not UsdPhysics.CollisionAPI(collider_prim):
raise ValueError(f"No collider schema present for prim '{prim_path}'.")
# retrieve the collision api
physx_collision_api = PhysxSchema.PhysxCollisionAPI(collider_prim)
if not physx_collision_api:
physx_collision_api = PhysxSchema.PhysxCollisionAPI.Apply(collider_prim)
# set enable/disable collision API
if collision_enabled is not None:
physx_collision_api.GetCollisionEnabledAttr().Set(collision_enabled)
# set contact offset
if contact_offset is not None:
physx_collision_api.GetContactOffsetAttr().Set(contact_offset)
# set rest offset
if rest_offset is not None:
physx_collision_api.GetRestOffsetAttr().Set(rest_offset)
# set torsional patch radius
if torsional_patch_radius is not None:
physx_collision_api.GetTorsionalPatchRadiusAttr().Set(torsional_patch_radius)
# set min torsional patch radius
if min_torsional_patch_radius is not None:
physx_collision_api.GetMinTorsionalPatchRadiusAttr().Set(min_torsional_patch_radius)
def apply_physics_material(prim_path: str, material_path: str, weaker_than_descendants: bool = False):
"""Apply a physics material to a prim.
Physics material can be applied only to a prim with physics-enabled on them. This includes having
a collision APIs, or deformable body APIs, or being a particle system.
Args:
prim_path (str): The prim path of parent.
material_path (str): The prim path of the material to apply.
Raises:
ValueError: If the material path does not exist on stage.
ValueError: When prim at specified path is not physics-enabled.
"""
# check if material exists
if not prim_utils.is_prim_path_valid(material_path):
raise ValueError(f"Physics material '{material_path}' does not exist.")
# get USD prim
prim = prim_utils.get_prim_at_path(prim_path)
# check if prim has collision applied on it
has_collider = prim.HasAPI(UsdPhysics.CollisionAPI)
has_deformable_body = prim.HasAPI(PhysxSchema.PhysxDeformableBodyAPI)
has_particle_system = prim.IsA(PhysxSchema.PhysxParticleSystem)
if not (has_collider or has_deformable_body or has_particle_system):
raise ValueError(
f"Cannot apply physics material on prim '{prim_path}'. It is neither a collider, nor a deformable body, nor a particle system."
)
# obtain material binding API
if prim.HasAPI(UsdShade.MaterialBindingAPI):
material_binding_api = UsdShade.MaterialBindingAPI(prim)
else:
material_binding_api = UsdShade.MaterialBindingAPI.Apply(prim)
# obtain the material prim
material = UsdShade.Material(prim_utils.get_prim_at_path(material_path))
# resolve token for weaker than descendants
if weaker_than_descendants:
binding_strength = UsdShade.Tokens.weakerThanDescendants
else:
binding_strength = UsdShade.Tokens.strongerThanDescendants
# apply the material
material_binding_api.Bind(material, bindingStrength=binding_strength, materialPurpose="physics")
def set_nested_articulation_properties(prim_path: str, **kwargs) -> None:
"""Set PhysX parameters on all articulations under specified prim-path.
Note:
Check the method meth:`set_articulation_properties` for keyword arguments.
Args:
prim_path (str): The prim path under which to search and apply articulation properties.
Keyword Args:
articulation_enabled (Optional[bool]): Whether the articulation should be enabled/disabled.
solver_position_iteration_count (Optional[int]): Solver position iteration counts for the body.
solver_velocity_iteration_count (Optional[int]): Solver velocity iteration counts for the body.
sleep_threshold (Optional[float]): Mass-normalized kinetic energy threshold below which an
actor may go to sleep.
stabilization_threshold (Optional[float]): The mass-normalized kinetic energy threshold below
which an articulation may participate in stabilization.
enable_self_collisions (Optional[bool]): Boolean defining whether self collisions should be
enabled or disabled.
"""
# get USD prim
prim = prim_utils.get_prim_at_path(prim_path)
# iterate over all prims under prim-path
all_prims = [prim]
while len(all_prims) > 0:
# get current prim
child_prim = all_prims.pop(0)
# set articulation properties
with contextlib.suppress(ValueError):
set_articulation_properties(prim_utils.get_prim_path(child_prim), **kwargs)
# add all children to tree
all_prims += child_prim.GetChildren()
def set_nested_rigid_body_properties(prim_path: str, **kwargs):
"""Set PhysX parameters on all rigid bodies under specified prim-path.
Note:
Check the method meth:`set_rigid_body_properties` for keyword arguments.
Args:
prim_path (str): The prim path under which to search and apply rigid-body properties.
Keyword Args:
rigid_body_enabled (Optional[bool]): Whether to enable or disable rigid body API.
solver_position_iteration_count (Optional[int]): Solver position iteration counts for the body.
solver_velocity_iteration_count (Optional[int]): Solver velocity iteration counts for the body.
linear_damping (Optional[float]): Linear damping coefficient.
angular_damping (Optional[float]): Angular damping coefficient.
max_linear_velocity (Optional[float]): Max allowable linear velocity for rigid body (in m/s).
max_angular_velocity (Optional[float]): Max allowable angular velocity for rigid body (in rad/s).
sleep_threshold (Optional[float]): Mass-normalized kinetic energy threshold below which an actor
may go to sleep.
stabilization_threshold (Optional[float]): Mass-normalized kinetic energy threshold below which
an actor may participate in stabilization.
max_depenetration_velocity (Optional[float]): The maximum depenetration velocity permitted to
be introduced by the solver (in m/s).
max_contact_impulse (Optional[float]): The limit on the impulse that may be applied at a contact.
enable_gyroscopic_forces (Optional[bool]): Enables computation of gyroscopic forces on the
rigid body.
disable_gravity (Optional[bool]): Disable gravity for the actor.
retain_accelerations (Optional[bool]): Carries over forces/accelerations over sub-steps.
"""
# get USD prim
prim = prim_utils.get_prim_at_path(prim_path)
# iterate over all prims under prim-path
all_prims = [prim]
while len(all_prims) > 0:
# get current prim
child_prim = all_prims.pop(0)
# set rigid-body properties
with contextlib.suppress(ValueError):
set_rigid_body_properties(prim_utils.get_prim_path(child_prim), **kwargs)
# add all children to tree
all_prims += child_prim.GetChildren()
def set_nested_collision_properties(prim_path: str, **kwargs):
"""Set the collider properties of all meshes under a specified prim path.
Note:
Check the method meth:`set_collision_properties` for keyword arguments.
Args:
prim_path (str): The prim path under which to search and apply collider properties.
Keyword Args:
collision_enabled (Optional[bool], optional): Whether to enable/disable collider.
contact_offset (Optional[float], optional): Contact offset of a collision shape (in m).
rest_offset (Optional[float], optional): Rest offset of a collision shape (in m).
torsional_patch_radius (Optional[float], optional): Defines the radius of the contact patch
used to apply torsional friction (in m).
min_torsional_patch_radius (Optional[float], optional): Defines the minimum radius of the
contact patch used to apply torsional friction (in m).
"""
# get USD prim
prim = prim_utils.get_prim_at_path(prim_path)
# iterate over all prims under prim-path
all_prims = [prim]
while len(all_prims) > 0:
# get current prim
child_prim = all_prims.pop(0)
# set collider properties
with contextlib.suppress(ValueError):
set_collision_properties(prim_utils.get_prim_path(child_prim), **kwargs)
# add all children to tree
all_prims += child_prim.GetChildren()
def apply_nested_physics_material(prim_path: str, material_path: str, weaker_than_descendants: bool = False):
"""Apply the physics material on all meshes under a specified prim path.
Physics material can be applied only to a prim with physics-enabled on them. This includes having
a collision APIs, or deformable body APIs, or being a particle system.
Args:
prim_path (str): The prim path under which to search and apply physics material.
material_path (str): The path to the physics material to apply.
weaker_than_descendants (bool, optional): Whether the material should override the
descendants materials. Defaults to False.
Raises:
ValueError: If the material path does not exist on stage.
"""
# check if material exists
if not prim_utils.is_prim_path_valid(material_path):
raise ValueError(f"Physics material '{material_path}' does not exist.")
# get USD prim
prim = prim_utils.get_prim_at_path(prim_path)
# iterate over all prims under prim-path
all_prims = [prim]
while len(all_prims) > 0:
# get current prim
child_prim = all_prims.pop(0)
# set physics material
with contextlib.suppress(ValueError):
apply_physics_material(prim_utils.get_prim_path(child_prim), material_path, weaker_than_descendants)
# add all children to tree
all_prims += child_prim.GetChildren()
......@@ -74,6 +74,7 @@ class Camera(SensorBase):
cfg (CameraCfg): The configuration parameters.
Raises:
RuntimeError: If no camera prim is found at the given path.
ValueError: If the sensor types intersect with in the unsupported list.
"""
# initialize base class
......@@ -111,6 +112,15 @@ class Camera(SensorBase):
" implementation from the omni.isaac.orbit.compat.camera module."
)
def __del__(self):
"""Unsubscribes from callbacks and detach from the replicator registry."""
# unsubscribe callbacks
super().__del__()
# delete from replicator registry
for _, annotators in self._rep_registry.items():
for annotator, render_product_path in zip(annotators, self._render_product_paths):
annotator.detach([render_product_path])
def __str__(self) -> str:
"""Returns: A string containing information about the instance."""
# message for class
......@@ -272,7 +282,7 @@ class Camera(SensorBase):
if orientations is not None:
if isinstance(orientations, np.ndarray):
orientations = torch.from_numpy(orientations).to(device=self._device)
elif not isinstance(orientations, torch.tensor):
elif not isinstance(orientations, torch.Tensor):
orientations = torch.tensor(orientations, device=self._device)
orientations = convert_orientation_convention(orientations, origin=convention, target="opengl")
# set the pose
......@@ -476,8 +486,8 @@ class Camera(SensorBase):
# -- pose of the cameras
self._data.pos_w = torch.zeros((self._view.count, 3), device=self._device)
self._data.quat_w_ros = torch.zeros((self._view.count, 4), device=self._device)
self._data.quat_w_world = torch.zeros((self._view.count, 4), device=self._device)
self._data.quat_w_opengl = torch.zeros((self._view.count, 4), device=self._device)
self._data.quat_w_world = torch.zeros_like(self._data.quat_w_ros)
self._data.quat_w_opengl = torch.zeros_like(self._data.quat_w_ros)
# -- intrinsic matrix
self._data.intrinsic_matrices = torch.zeros((self._view.count, 3, 3), device=self._device)
self._data.image_shape = self.image_shape
......@@ -551,12 +561,8 @@ class Camera(SensorBase):
self._data.quat_w_opengl[env_ids] = quat_opengl
# save world and ros convention
self._data.quat_w_world[env_ids] = convert_orientation_convention(
quat_opengl.clone(), origin="opengl", target="world"
)
self._data.quat_w_ros[env_ids] = convert_orientation_convention(
quat_opengl.clone(), origin="opengl", target="ros"
)
self._data.quat_w_world[env_ids] = convert_orientation_convention(quat_opengl, origin="opengl", target="world")
self._data.quat_w_ros[env_ids] = convert_orientation_convention(quat_opengl, origin="opengl", target="ros")
def _create_annotator_data(self):
"""Create the buffers to store the annotator data.
......
......@@ -321,7 +321,7 @@ def convert_orientation_convention(
torch.Tensor: Quaternion of form `(w, x, y, z)` with shape (..., 4) in target convention
"""
if target == origin:
return orientation
return orientation.clone()
# -- unify input type
if origin == "ros":
......@@ -363,4 +363,4 @@ def convert_orientation_convention(
)
return math_utils.quat_from_matrix(rotm)
else:
return quat_gl
return quat_gl.clone()
......@@ -33,8 +33,8 @@ class PinholeCameraCfg(SpawnerCfg):
Note:
Currently only "pinhole" is supported.
"""
clipping_range: tuple[float, float] = (1.0, 1000000.0)
"""Near and far clipping distances (in m). Defaults to (1.0, 1000000.0)."""
clipping_range: tuple[float, float] = (1.0, 1e6)
"""Near and far clipping distances (in m). Defaults to (1.0, 1e6)."""
focal_length: float = 24.0
"""Perspective focal length (in cm). Defaults to 24.0cm.
......
......@@ -190,7 +190,8 @@ class TerrainImporter:
if key in self.meshes:
raise ValueError(f"Mesh with key {key} already exists. Existing keys: {self.meshes.keys()}.")
# add the prim path
prim_utils.create_prim(self.cfg.prim_path + f"/{key}", usd_path=usd_path)
cfg = sim_utils.UsdFileCfg(usd_path=usd_path)
cfg.func(self.cfg.prim_path + f"/{key}", cfg)
# traverse the prim and get the collision mesh
# THINK: Should the user specify the collision mesh?
......
......@@ -12,7 +12,8 @@ Some of these are imported from the module `omni.isaac.core.utils.torch` for con
import numpy as np
import torch
import torch.nn.functional
from typing import Optional, Sequence, Tuple, Union
from typing import Optional, Tuple, Union
from typing_extensions import Literal
from omni.isaac.core.utils.torch.maths import normalize, scale_transform, unscale_transform
from omni.isaac.core.utils.torch.rotations import (
......@@ -135,6 +136,7 @@ def matrix_from_quat(quaternions: torch.Tensor) -> torch.Tensor:
Args:
quaternions: quaternions with real part first,
as tensor of shape (..., 4).
Returns:
Rotation matrices as tensor of shape (..., 3, 3).
......@@ -162,42 +164,52 @@ def matrix_from_quat(quaternions: torch.Tensor) -> torch.Tensor:
return o.reshape(quaternions.shape[:-1] + (3, 3))
def convert_quat(quat: Union[torch.Tensor, Sequence[float]], to: Optional[str] = "xyzw") -> torch.Tensor:
def convert_quat(
quat: Union[torch.Tensor, np.ndarray], to: Literal["xyzw", "wxyz"] = "xyzw"
) -> Union[torch.Tensor, np.ndarray]:
"""Converts quaternion from one convention to another.
The convention to convert TO is specified as an optional argument. If to == 'xyzw',
then the input is in 'wxyz' format, and vice-versa.
Args:
quat (Union[torch.Tensor, Sequence[float]]): Input quaternion of shape (..., 4).
to (Optional[str], optional): Convention to convert quaternion to.. Defaults to "xyzw".
quat (Union[torch.Tensor, np.ndarray]): Input quaternion of shape (..., 4).
to (Literal["xyzw", "wxyz"], optional): Convention to convert quaternion to.. Defaults to "xyzw".
Returns:
Union[torch.Tensor, np.ndarray]: The converted quaternion in specified convention.
Raises:
ValueError: Invalid input argument `to`, i.e. not "xyzw" or "wxyz".
ValueError: Invalid shape of input `quat`, i.e. not (..., 4,).
Returns:
torch.Tensor: The converted quaternion in specified convention.
"""
# convert to torch (sanity check)
if not isinstance(quat, torch.Tensor):
if isinstance(quat, np.ndarray):
quat = torch.from_numpy(quat)
else:
quat = torch.tensor(quat, dtype=float)
# check input is correct
if quat.shape[-1] != 4:
msg = f"Expected input quaternion shape mismatch: {quat.shape} != (..., 4)."
raise ValueError(msg)
if to not in ["xyzw", "wxyz"]:
msg = f"Expected input argument `to` to be 'xyzw' or 'wxyz'. Received: {to}."
raise ValueError(msg)
# check if input is numpy array (we support this backend since some classes use numpy)
if isinstance(quat, np.ndarray):
# use numpy functions
if to == "xyzw":
# wxyz -> xyzw
return np.roll(quat, -1, axis=-1)
else:
# xyzw -> wxyz
return np.roll(quat, 1, axis=-1)
else:
# convert to torch (sanity check)
if not isinstance(quat, torch.Tensor):
quat = torch.tensor(quat, dtype=float)
# convert to specified quaternion type
if to == "xyzw":
# wxyz -> xyzw
return quat.roll(-1, dims=-1)
elif to == "wxyz":
else:
# xyzw -> wxyz
return quat.roll(1, dims=-1)
else:
raise ValueError(f"Choose a valid `to` argument (xyzw or wxyz). Received: {to}")
@torch.jit.script
......@@ -245,9 +257,7 @@ def quat_from_euler_xyz(roll: torch.Tensor, pitch: torch.Tensor, yaw: torch.Tens
@torch.jit.script
def _sqrt_positive_part(x: torch.Tensor) -> torch.Tensor:
"""
Returns torch.sqrt(torch.max(0, x))
but with a zero subgradient where x is 0.
"""Returns torch.sqrt(torch.max(0, x)) but with a zero sub-gradient where x is 0.
Reference:
Based on PyTorch3D (https://github.com/facebookresearch/pytorch3d/blob/main/pytorch3d/transforms/rotation_conversions.py#L91-L99)
......@@ -323,13 +333,12 @@ def quat_from_matrix(matrix: torch.Tensor) -> torch.Tensor:
def _axis_angle_rotation(axis: str, angle: torch.Tensor) -> torch.Tensor:
"""
Return the rotation matrices for one of the rotations about an axis
of which Euler angles describe, for each value of the angle given.
"""Return the rotation matrices for one of the rotations about an axis of which Euler angles describe,
for each value of the angle given.
Args:
axis: Axis label "X" or "Y or "Z".
angle: any shape tensor of Euler angles in radians
angle: Any shape tensor of Euler angles in radians.
Returns:
Rotation matrices as tensor of shape (..., 3, 3).
......
......@@ -36,7 +36,7 @@ from omni.isaac.core.utils.torch import set_seed
from omni.isaac.core.utils.viewports import set_camera_view
from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.sensors.camera import Camera, PinholeCameraCfg
from omni.isaac.orbit.utils.math import convert_quat
from omni.isaac.orbit.utils.timer import Timer
......
......@@ -33,7 +33,7 @@ from omni.isaac.core.objects.cuboid import DynamicCuboid
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.sensors.height_scanner import HeightScanner, HeightScannerCfg
from omni.isaac.orbit.compat.sensors.height_scanner.utils import create_points_from_grid, plot_height_grid
from omni.isaac.orbit.utils.math import convert_quat
......
......@@ -21,7 +21,7 @@ import omni.isaac.core.utils.stage as stage_utils
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script shows the issue with renderer in Isaac Sim that affects episodic resets.
The first few images of every new episode are not updated. They take multiple steps to update
and have the same image as the previous episode for the first few steps.
```
# run with cube
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/isaacsim/check_camera.py --scenario cube
# run with anymal
_isaac_sim/python.sh source/extensions/omni.isaac.orbit/test/isaacsim/check_camera.py --scenario anymal
```
"""
"""Launch Isaac Sim Simulator first."""
import argparse
# omni-isaac-orbit
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser(
description="This script shows the issue with renderer in Isaac Sim that affects episodic resets."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.")
parser.add_argument("--scenario", type=str, default="anymal", help="Scenario to load.", choices=["anymal", "cube"])
args_cli = parser.parse_args()
# launch omniverse app
config = {"headless": args_cli.headless}
simulation_app = SimulationApp(config)
"""Rest everything follows."""
import numpy as np
import os
import random
import omni.isaac.core.utils.nucleus as nucleus_utils
import omni.isaac.core.utils.prims as prim_utils
import omni.replicator.core as rep
from omni.isaac.core.articulations import ArticulationView
from omni.isaac.core.prims import GeometryPrim, RigidPrim, RigidPrimView
from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view
from omni.isaac.core.world import World
from PIL import Image, ImageChops
from pxr import Gf, UsdGeom
# check nucleus connection
if nucleus_utils.get_assets_root_path() is None:
msg = (
"Unable to perform Nucleus login on Omniverse. Assets root path is not set.\n"
"\tPlease check: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html#omniverse-nucleus"
)
raise RuntimeError(msg)
ISAAC_NUCLEUS_DIR = f"{nucleus_utils.get_assets_root_path()}/Isaac"
"""Path to the `Isaac` directory on the NVIDIA Nucleus Server."""
def main():
"""Runs a camera sensor from orbit."""
# Load kit helper
world = World(physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cpu")
# Set main camera
set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Enable flatcache which avoids passing data over to USD structure
# this speeds up the read-write operation of GPU buffers
if world.get_physics_context().use_gpu_pipeline:
world.get_physics_context().enable_flatcache(True)
# Enable hydra scene-graph instancing
# this is needed to visualize the scene when flatcache is enabled
set_carb_setting(world._settings, "/persistent/omnihydra/useSceneGraphInstancing", True)
# Populate scene
# Ground
world.scene.add_default_ground_plane()
# Lights-1
prim_utils.create_prim(
"/World/Light/GreySphere",
"SphereLight",
translation=(4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (0.75, 0.75, 0.75)},
)
# Lights-2
prim_utils.create_prim(
"/World/Light/WhiteSphere",
"SphereLight",
translation=(-4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (1.0, 1.0, 1.0)},
)
# Xform to hold objects
if args_cli.scenario == "cube":
prim_utils.create_prim("/World/Objects", "Xform")
# Random objects
for i in range(8):
# sample random position
position = np.random.rand(3) - np.asarray([0.05, 0.05, -1.0])
position *= np.asarray([1.5, 1.5, 0.5])
# create prim
prim_type = random.choice(["Cube", "Sphere", "Cylinder"])
_ = prim_utils.create_prim(
f"/World/Objects/Obj_{i:02d}",
prim_type,
translation=position,
scale=(0.25, 0.25, 0.25),
semantic_label=prim_type,
)
# add rigid properties
GeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True)
rigid_obj = RigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0)
# cast to geom prim
geom_prim = getattr(UsdGeom, prim_type)(rigid_obj.prim)
# set random color
color = Gf.Vec3f(random.random(), random.random(), random.random())
geom_prim.CreateDisplayColorAttr()
geom_prim.GetDisplayColorAttr().Set([color])
# Setup camera sensor on the world
cam_prim_path = "/World/CameraSensor"
else:
# Robot
prim_utils.create_prim(
"/World/Robot",
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_instanceable.usd",
translation=(0.0, 0.0, 0.6),
)
# Setup camera sensor on the robot
cam_prim_path = "/World/CameraSensor"
# Create camera
cam_prim = prim_utils.create_prim(
cam_prim_path,
prim_type="Camera",
translation=(5.0, 5.0, 5.0),
orientation=(0.33985113, 0.17591988, 0.42470818, 0.82047324),
)
_ = UsdGeom.Camera(cam_prim)
# Get render product
render_prod_path = rep.create.render_product(cam_prim_path, resolution=(640, 480))
# create annotator node
rep_registry = {}
for name in ["rgb", "distance_to_image_plane"]:
# create annotator
rep_annotator = rep.AnnotatorRegistry.get_annotator(name, device="cpu")
rep_annotator.attach(render_prod_path)
# add to registry
rep_registry[name] = rep_annotator
# Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera", args_cli.scenario)
os.makedirs(output_dir, exist_ok=True)
# Create a view of the stuff we want to see
if args_cli.scenario == "cube":
view: RigidPrimView = world.scene.add(RigidPrimView("/World/Objects/.*", name="my_object"))
else:
view: ArticulationView = world.scene.add(ArticulationView("/World/Robot", name="my_object"))
# Play simulator
world.reset()
# Get initial state
if args_cli.scenario == "cube":
initial_pos, initial_quat = view.get_world_poses()
initial_joint_pos = None
initial_joint_vel = None
else:
initial_pos, initial_quat = view.get_world_poses()
initial_joint_pos = view.get_joint_positions()
initial_joint_vel = view.get_joint_velocities()
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
for _ in range(5):
world.step(render=True)
# Counter
count = 0
prev_im = None
# make episode directory
episode_count = 0
episode_dir = os.path.join(output_dir, f"episode_{episode_count:06d}")
os.makedirs(episode_dir, exist_ok=True)
# Simulate physics
while simulation_app.is_running():
# If simulation is stopped, then exit.
if world.is_stopped():
break
# If simulation is paused, then skip.
if not world.is_playing():
world.step(render=not args_cli.headless)
continue
# Reset on intervals
if count % 25 == 0:
# reset all the state
view.set_world_poses(initial_pos, initial_quat)
if initial_joint_pos is not None:
view.set_joint_positions(initial_joint_pos)
if initial_joint_vel is not None:
view.set_joint_velocities(initial_joint_vel)
# make a new episode directory
episode_dir = os.path.join(output_dir, f"episode_{episode_count:06d}")
os.makedirs(episode_dir, exist_ok=True)
# reset counters
count = 0
episode_count += 1
# Step simulation
for _ in range(15):
world.step(render=False)
world.render()
# Update camera data
rgb_data = rep_registry["rgb"].get_data()
depth_data = rep_registry["distance_to_image_plane"].get_data()
# Show current image number
print(f"[Epi {episode_count:03d}] Current image number: {count:06d}")
# Save data
curr_im = Image.fromarray(rgb_data)
curr_im.save(os.path.join(episode_dir, f"{count:06d}_rgb.png"))
# Save diff
if prev_im is not None:
diff_im = ImageChops.difference(curr_im, prev_im)
# convert to grayscale and threshold
diff_im = diff_im.convert("L")
threshold = 30
diff_im = diff_im.point(lambda p: p > threshold and 255)
# Save all of them together
dst_im = Image.new("RGB", (curr_im.width + prev_im.width + diff_im.width, diff_im.height))
dst_im.paste(prev_im, (0, 0))
dst_im.paste(curr_im, (prev_im.width, 0))
dst_im.paste(diff_im, (2 * prev_im.width, 0))
dst_im.save(os.path.join(episode_dir, f"{count:06d}_diff.png"))
# Save to previous
prev_im = curr_im.copy()
# Update counter
count += 1
# Print camera info
print("Received shape of rgb image: ", rgb_data.shape)
print("Received shape of depth image: ", depth_data.shape)
print("-------------------------------")
if __name__ == "__main__":
# Runs the main function
main()
# Close the simulator
simulation_app.close()
......@@ -17,7 +17,9 @@ import argparse
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(
description="This script shows the issue in Isaac Sim with GPU simulation of floating robots."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--num_robots", type=int, default=128, help="Number of robots to spawn.")
parser.add_argument(
......
......@@ -19,7 +19,9 @@ import argparse
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(
description="This script shows how to use replicator to randomly change the textures of a USD scene."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
args_cli = parser.parse_args()
......
......@@ -59,7 +59,7 @@ class TestUsdVisualizationMarkers(unittest.TestCase):
# check number of markers
self.assertEqual(test_marker.num_prototypes, 1)
def test_usd_cpu_marker(self):
def test_usd_marker(self):
"""Test with marker from a USD."""
# create a marker
test_marker = VisualizationMarkers("/World/Visuals/test_frames", FRAME_MARKER_CFG)
......@@ -82,29 +82,6 @@ class TestUsdVisualizationMarkers(unittest.TestCase):
# asset that count is correct
self.assertEqual(test_marker.count, num_frames)
def test_usd_gpu_marker(self):
"""Test with marker from a USD."""
# create a marker
test_marker = VisualizationMarkers("/World/Visuals/test_frames", FRAME_MARKER_CFG)
# play the simulation
self.sim.reset()
# create a buffer
num_frames = 0
# run with randomization of poses
for count in range(1000):
# sample random poses
if count % 50 == 0:
num_frames = torch.randint(10, 1000, (1,)).item()
frame_translations = torch.randn((num_frames, 3), device=self.sim.device)
frame_rotations = random_orientation(num_frames, device=self.sim.device)
# set the marker
test_marker.visualize(translations=frame_translations, orientations=frame_rotations)
# update the kit
self.sim.step()
# asset that count is correct
self.assertEqual(test_marker.count, num_frames)
def test_usd_marker_color(self):
"""Test with marker from a USD with its color modified."""
# create a marker
......
......@@ -34,16 +34,15 @@ simulation_app = SimulationApp(config)
import torch
import carb
import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.cloner import GridCloner
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.assets import Articulation
from omni.isaac.orbit.assets.articulation.config.anymal import ANYMAL_C_CFG
from omni.isaac.orbit.assets.config.anymal import ANYMAL_C_CFG
from omni.isaac.orbit.sensors.contact_sensor import ContactSensor, ContactSensorCfg
"""
......@@ -129,7 +128,8 @@ def main():
# Define simulation stepping
decimation = 4
sim_dt = decimation * sim.get_physics_dt()
physics_dt = sim.get_physics_dt()
sim_dt = decimation * physics_dt
sim_time = 0.0
count = 0
# Simulate physics
......@@ -153,19 +153,18 @@ def main():
# perform 4 steps
for _ in range(decimation):
# apply actions
robot.set_joint_position_targets(robot.data.default_joint_pos)
robot.set_joint_position_target(robot.data.default_joint_pos)
# write commands to sim
robot.write_data_to_sim()
# perform step
sim.step(render=not args_cli.headless)
# fetch data
robot.fetch_data_from_sim()
robot.update(physics_dt)
# update sim-time
sim_time += sim_dt
count += 1
# update the buffers
if sim.is_playing():
robot.update(sim_dt)
contact_sensor.update(sim_dt, force_recompute=True)
if count % 100 == 0:
print("Sim-time: ", sim_time)
......
......@@ -2,25 +2,14 @@
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script shows how to use the camera sensor from the Orbit framework.
The camera sensor is created and interfaced through the Omniverse Replicator API. However, instead of using
the simulator or OpenGL convention for the camera, we use the robotics or ROS convention.
"""
# ignore private usage of variables warning
# pyright: reportPrivateUsage=none
"""Launch Isaac Sim Simulator first."""
import argparse
# omni-isaac-orbit
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser(description="Camera Sensor Test Script")
parser.add_argument("--gpu", action="store_false", default=False, help="Use GPU device for camera rendering output.")
args_cli = parser.parse_args()
# launch omniverse app
app_launcher = AppLauncher(headless=True)
simulation_app = app_launcher.app
......@@ -32,21 +21,21 @@ import numpy as np
import os
import random
import scipy.spatial.transform as tf
import shutil
import traceback
import unittest
import carb
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
import omni.replicator.core as rep
from omni.isaac.core.prims import RigidPrim
from omni.isaac.core.prims import GeometryPrim, RigidPrim
from omni.isaac.core.simulation_context import SimulationContext
from pxr import Gf, Usd, UsdGeom
from omni.isaac.orbit.compat.utils.kit import create_ground_plane
from omni.isaac.orbit.sensors.camera import Camera, CameraCfg
from omni.isaac.orbit.sim import PinholeCameraCfg
from omni.isaac.orbit.utils import convert_dict_to_backend
from omni.isaac.orbit.utils.kit import create_ground_plane
from omni.isaac.orbit.utils.math import convert_quat
from omni.isaac.orbit.utils.timer import Timer
......@@ -77,34 +66,38 @@ class TestCamera(unittest.TestCase):
),
colorize=False,
)
# Create a new stage
stage_utils.create_new_stage()
# Simulation time-step
self.dt = 0.01
# Load kit helper
self.sim = SimulationContext(
physics_dt=self.dt, rendering_dt=self.dt, backend="torch", device="cuda" if args_cli.gpu else "cpu"
)
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="torch", device="cpu")
# populate scene
self._populate_scene()
# load stage
stage_utils.update_stage()
def tearDown(self) -> None:
def tearDown(self):
"""Stops simulator after each test."""
# close all the opened viewport from before.
rep.vp_manager.destroy_hydra_textures()
rep.vp_manager.destroy_hydra_textures("Replicator")
# stop simulation
self.sim.stop()
# note: cannot use self.sim.stop() since it does one render step after stopping!! This doesn't make sense :(
self.sim._timeline.stop()
# clear the stage
self.sim.clear()
self.sim.clear_instance()
"""
Tests
"""
def test_camera_init(self) -> None:
def test_camera_init(self):
"""Test camera initialization."""
# Create camera
camera = Camera(self.camera_cfg)
# Play sim
self.sim.play()
self.sim.reset()
# Check if camera is initialized
self.assertTrue(camera._is_initialized)
# Check if camera prim is set correctly and that it is a camera prim
......@@ -132,12 +125,16 @@ class TestCamera(unittest.TestCase):
# check image data
for im_data in camera.data.output.to_dict().values():
self.assertTrue(im_data.shape == (1, self.camera_cfg.height, self.camera_cfg.width))
# delete camera
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
camera.__del__()
def test_camera_resolution(self) -> None:
def test_camera_resolution(self):
"""Test camera resolution is correctly set."""
# Create camera
camera = Camera(self.camera_cfg)
# Play sim
self.sim.play()
self.sim.reset()
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
......@@ -147,40 +144,43 @@ class TestCamera(unittest.TestCase):
# access image data and compare shapes
for im_data in camera.data.output.to_dict().values():
self.assertTrue(im_data.shape == (1, self.camera_cfg.height, self.camera_cfg.width))
# delete camera
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
camera.__del__()
def test_camera_init_offset(self) -> None:
"""Test camera initialization with offset."""
def test_camera_init_offset(self):
"""Test camera initialization with offset using different conventions."""
# define the same offset in all conventions
cam_cfg_offset_ros = copy.copy(self.camera_cfg)
# -- ROS convention
cam_cfg_offset_ros = copy.deepcopy(self.camera_cfg)
cam_cfg_offset_ros.offset = CameraCfg.OffsetCfg(
pos=POSITION,
rot=QUAT_ROS,
convention="ros",
)
cam_cfg_offset_ros.prim_path = "/World/CameraOffsetRos"
cam_cfg_offset_opengl = copy.copy(self.camera_cfg)
camera_ros = Camera(cam_cfg_offset_ros)
# -- OpenGL convention
cam_cfg_offset_opengl = copy.deepcopy(self.camera_cfg)
cam_cfg_offset_opengl.offset = CameraCfg.OffsetCfg(
pos=POSITION,
rot=QUAT_OPENGL,
convention="opengl",
)
cam_cfg_offset_opengl.prim_path = "/World/CameraOffsetOpengl"
cam_cfg_offset_world = copy.copy(self.camera_cfg)
camera_opengl = Camera(cam_cfg_offset_opengl)
# -- World convention
cam_cfg_offset_world = copy.deepcopy(self.camera_cfg)
cam_cfg_offset_world.offset = CameraCfg.OffsetCfg(
pos=POSITION,
rot=QUAT_WORLD,
convention="world",
)
cam_cfg_offset_world.prim_path = "/World/CameraOffsetWorld"
camera_ros = Camera(cam_cfg_offset_ros)
camera_opengl = Camera(cam_cfg_offset_opengl)
camera_world = Camera(cam_cfg_offset_world)
# play sim
self.sim.play()
self.sim.reset()
# retrieve camera pose
prim_tf_ros = camera_ros._sensor_prims[0].ComputeLocalToWorldTransform(Usd.TimeCode.Default())
......@@ -192,48 +192,51 @@ class TestCamera(unittest.TestCase):
prim_tf_world = np.transpose(prim_tf_world)
# check that all transforms are set correctly
self.assertTrue(np.allclose(prim_tf_ros[0:3, 3], cam_cfg_offset_ros.offset.pos))
self.assertTrue(np.allclose(prim_tf_opengl[0:3, 3], cam_cfg_offset_opengl.offset.pos))
self.assertTrue(np.allclose(prim_tf_world[0:3, 3], cam_cfg_offset_world.offset.pos))
self.assertTrue(
np.allclose(
np.testing.assert_allclose(prim_tf_ros[0:3, 3], cam_cfg_offset_ros.offset.pos)
np.testing.assert_allclose(prim_tf_opengl[0:3, 3], cam_cfg_offset_opengl.offset.pos)
np.testing.assert_allclose(prim_tf_world[0:3, 3], cam_cfg_offset_world.offset.pos)
np.testing.assert_allclose(
convert_quat(tf.Rotation.from_matrix(prim_tf_ros[:3, :3]).as_quat(), "wxyz"),
cam_cfg_offset_opengl.offset.rot,
rtol=1e-5,
)
)
self.assertTrue(
np.allclose(
np.testing.assert_allclose(
convert_quat(tf.Rotation.from_matrix(prim_tf_opengl[:3, :3]).as_quat(), "wxyz"),
cam_cfg_offset_opengl.offset.rot,
rtol=1e-5,
)
)
self.assertTrue(
np.allclose(
np.testing.assert_allclose(
convert_quat(tf.Rotation.from_matrix(prim_tf_world[:3, :3]).as_quat(), "wxyz"),
cam_cfg_offset_opengl.offset.rot,
)
rtol=1e-5,
)
# check if transform correctly set in output
self.assertTrue(np.allclose(camera_ros.data.pos_w[0], cam_cfg_offset_ros.offset.pos))
self.assertTrue(np.allclose(camera_ros.data.quat_w_ros[0], QUAT_ROS))
self.assertTrue(np.allclose(camera_ros.data.quat_w_opengl[0], QUAT_OPENGL))
self.assertTrue(np.allclose(camera_ros.data.quat_w_world[0], QUAT_WORLD))
def test_multi_camera_init(self) -> None:
"""Test camera initialization with offset."""
# define the same offset in all conventions
cam_cfg_1 = copy.copy(self.camera_cfg)
np.testing.assert_allclose(camera_ros.data.pos_w[0], cam_cfg_offset_ros.offset.pos, rtol=1e-5)
np.testing.assert_allclose(camera_ros.data.quat_w_ros[0], QUAT_ROS, rtol=1e-5)
np.testing.assert_allclose(camera_ros.data.quat_w_opengl[0], QUAT_OPENGL, rtol=1e-5)
np.testing.assert_allclose(camera_ros.data.quat_w_world[0], QUAT_WORLD, rtol=1e-5)
# delete all cameras
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
camera_ros.__del__()
camera_opengl.__del__()
camera_world.__del__()
def test_multi_camera_init(self):
"""Test multi-camera initialization."""
# create two cameras with different prim paths
# -- camera 1
cam_cfg_1 = copy.deepcopy(self.camera_cfg)
cam_cfg_1.prim_path = "/World/Camera_1"
cam_cfg_2 = copy.copy(self.camera_cfg)
cam_cfg_2.prim_path = "/World/Camera_2"
cam_1 = Camera(cam_cfg_1)
# -- camera 2
cam_cfg_2 = copy.deepcopy(self.camera_cfg)
cam_cfg_2.prim_path = "/World/Camera_2"
cam_2 = Camera(cam_cfg_2)
# play sim
self.sim.play()
self.sim.reset()
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
......@@ -251,34 +254,45 @@ class TestCamera(unittest.TestCase):
for im_data in cam.data.output.to_dict().values():
self.assertTrue(im_data.shape == (1, self.camera_cfg.height, self.camera_cfg.width))
def test_camera_set_world_poses(self) -> None:
# delete camera
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
cam_1.__del__()
cam_2.__del__()
def test_camera_set_world_poses(self):
"""Test camera function to set specific world pose."""
camera = Camera(self.camera_cfg)
# play sim
self.sim.play()
self.sim.reset()
# set new pose
camera.set_world_poses([POSITION], [QUAT_WORLD], convention="world")
self.assertTrue(np.allclose(camera.data.pos_w, [POSITION]))
self.assertTrue(np.allclose(camera.data.quat_w_world, [QUAT_WORLD]))
np.testing.assert_allclose(camera.data.pos_w, [POSITION], rtol=1e-5)
np.testing.assert_allclose(camera.data.quat_w_world, [QUAT_WORLD], rtol=1e-5)
# delete camera
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
camera.__del__()
def test_camera_set_world_poses_from_view(self) -> None:
def test_camera_set_world_poses_from_view(self):
"""Test camera function to set specific world pose from view."""
camera = Camera(self.camera_cfg)
# play sim
self.sim.play()
self.sim.reset()
# set new pose
camera.set_world_poses_from_view([POSITION], [[0.0, 0.0, 0.0]])
self.assertTrue(np.allclose(camera.data.pos_w, [POSITION]))
self.assertTrue(np.allclose(camera.data.quat_w_ros, [QUAT_ROS]))
np.testing.assert_allclose(camera.data.pos_w, [POSITION], rtol=1e-5)
np.testing.assert_allclose(camera.data.quat_w_ros, [QUAT_ROS], rtol=1e-5)
# delete camera
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
camera.__del__()
def test_intrinsic_matrix(self) -> None:
def test_intrinsic_matrix(self):
"""Checks that the camera's set and retrieve methods work for intrinsic matrix."""
camera_cfg = copy.copy(self.camera_cfg)
camera_cfg = copy.deepcopy(self.camera_cfg)
camera_cfg.height = 240
camera_cfg.width = 320
camera = Camera(camera_cfg)
# play sim
self.sim.play()
self.sim.reset()
# Desired properties (obtained from realsense camera at 320x240 resolution)
rs_intrinsic_matrix = [229.31640625, 0.0, 164.810546875, 0.0, 229.826171875, 122.1650390625, 0.0, 0.0, 1.0]
rs_intrinsic_matrix = np.array(rs_intrinsic_matrix).reshape(3, 3)
......@@ -302,6 +316,9 @@ class TestCamera(unittest.TestCase):
# This is a bug in the simulator.
self.assertAlmostEqual(rs_intrinsic_matrix[0, 0], K[0, 0], 4)
# self.assertAlmostEqual(rs_intrinsic_matrix[1, 1], K[1, 1], 4)
# delete camera
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
camera.__del__()
def test_throughput(self):
"""Checks that the single camera gets created properly with a rig."""
......@@ -312,15 +329,14 @@ class TestCamera(unittest.TestCase):
# Create replicator writer
rep_writer = rep.BasicWriter(output_dir=temp_dir, frame_padding=3)
# create camera
camera_cfg = copy.copy(self.camera_cfg)
camera_cfg = copy.deepcopy(self.camera_cfg)
camera_cfg.height = 480
camera_cfg.width = 640
camera = Camera(camera_cfg)
# Play simulator
self.sim.play()
self.sim.reset()
# Set camera pose
camera.set_world_poses_from_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
self.sim.reset()
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
......@@ -350,6 +366,9 @@ class TestCamera(unittest.TestCase):
# Check image data
for im_data in camera.data.output.values():
self.assertTrue(im_data.shape == (1, camera_cfg.height, camera_cfg.width))
# delete camera
# TODO: Why do need to delete camera manually. Shouldn't it be deleted automatically?
camera.__del__()
"""
Helper functions.
......@@ -382,21 +401,22 @@ class TestCamera(unittest.TestCase):
position *= np.asarray([1.5, 1.5, 0.5])
# create prim
prim_type = random.choice(["Cube", "Sphere", "Cylinder"])
_ = prim_utils.create_prim(
prim = prim_utils.create_prim(
f"/World/Objects/Obj_{i:02d}",
prim_type,
translation=position,
scale=(0.25, 0.25, 0.25),
semantic_label=prim_type,
)
# add rigid properties
rigid_obj = RigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0)
# cast to geom prim
geom_prim = getattr(UsdGeom, prim_type)(rigid_obj.prim)
geom_prim = getattr(UsdGeom, prim_type)(prim)
# set random color
color = Gf.Vec3f(random.random(), random.random(), random.random())
geom_prim.CreateDisplayColorAttr()
geom_prim.GetDisplayColorAttr().Set([color])
# add rigid properties
GeometryPrim(f"/World/Objects/Obj_{i:02d}", collision=True)
RigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0)
if __name__ == "__main__":
......
......@@ -3,10 +3,21 @@
#
# SPDX-License-Identifier: BSD-3-Clause
import argparse
import matplotlib.pyplot as plt
import numpy as np
"""Launch Isaac Sim Simulator first."""
import os
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app
# note: we only need to do this because of `TerrainImporter` which uses Omniverse functions
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
app_launcher = AppLauncher(headless=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
import argparse
import trimesh
import omni.isaac.orbit.terrains.height_field as hf_gen
......@@ -242,3 +253,6 @@ if __name__ == "__main__":
test_discrete_obstacles_terrain(difficulty=0.25, obstacle_height_mode="fixed")
test_wave_terrain(difficulty=0.25)
test_stepping_stones_terrain(difficulty=1.0)
# close the app
simulation_app.close()
......@@ -3,8 +3,21 @@
#
# SPDX-License-Identifier: BSD-3-Clause
import argparse
"""Launch Isaac Sim Simulator first."""
import os
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app
# note: we only need to do this because of `TerrainImporter` which uses Omniverse functions
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
app_launcher = AppLauncher(headless=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
import argparse
import trimesh
import omni.isaac.orbit.terrains.trimesh as mesh_gen
......@@ -404,3 +417,6 @@ if __name__ == "__main__":
test_repeated_objects_terrain(difficulty=0.75, object_type="pyramid")
test_repeated_objects_terrain(difficulty=0.75, object_type="cylinder")
test_repeated_objects_terrain(difficulty=0.75, object_type="box")
# close the app
simulation_app.close()
......@@ -3,9 +3,21 @@
#
# SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
import argparse
import os
from omni.isaac.orbit.app import AppLauncher
# launch omniverse app
# note: we only need to do this because of `TerrainImporter` which uses Omniverse functions
app_experience = f"{os.environ['EXP_PATH']}/omni.isaac.sim.python.gym.headless.kit"
app_launcher = AppLauncher(headless=True, experience=app_experience)
simulation_app = app_launcher.app
"""Rest everything follows."""
import shutil
from omni.isaac.orbit.terrains.config.rough import ROUGH_TERRAINS_CFG
......@@ -26,3 +38,6 @@ if __name__ == "__main__":
ROUGH_TERRAINS_CFG.curriculum = False
# generate terrains
terrain_generator = TerrainGenerator(cfg=ROUGH_TERRAINS_CFG)
# close the simulation app
simulation_app.close()
......@@ -33,7 +33,7 @@ import argparse
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="This script shows how to use the terrain importer.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--geom_sphere", action="store_true", default=False, help="Whether to use sphere mesh or shape.")
parser.add_argument(
......
......@@ -13,7 +13,7 @@ import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.torch as torch_utils
from omni.isaac.core.articulations import ArticulationView
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg
......
......@@ -12,7 +12,7 @@ import omni.isaac.core.utils.nucleus as nucleus_utils
import omni.isaac.core.utils.prims as prim_utils
from omni.isaac.core.articulations import ArticulationView
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg
......
......@@ -13,7 +13,7 @@ import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.torch as torch_utils
from omni.isaac.core.articulations import ArticulationView
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit_envs.isaac_env import IsaacEnv, VecEnvIndices, VecEnvObs
from omni.isaac.orbit_envs.isaac_env_cfg import EnvCfg, IsaacEnvCfg
......
......@@ -10,7 +10,7 @@ from typing import List
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import StaticMarker
from omni.isaac.orbit.compat.utils.mdp import ObservationManager, RewardManager
from omni.isaac.orbit.controllers.differential_inverse_kinematics import DifferentialInverseKinematics
......
......@@ -9,7 +9,7 @@ import torch
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import PointMarker, StaticMarker
from omni.isaac.orbit.compat.utils.mdp import ObservationManager, RewardManager
from omni.isaac.orbit.controllers.differential_inverse_kinematics import DifferentialInverseKinematics
......
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This script shows how to use the camera sensor from the Orbit framework.
The camera sensor is created and interfaced through the Omniverse Replicator API. However, instead of using
the simulator or OpenGL convention for the camera, we use the robotics or ROS convention.
"""
"""Launch Isaac Sim Simulator first."""
import argparse
# omni-isaac-orbit
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.")
parser.add_argument("--draw", action="store_true", default=False, help="Draw the obtained pointcloud on viewport.")
args_cli = parser.parse_args()
# launch omniverse app
config = {"headless": args_cli.headless}
simulation_app = SimulationApp(config)
"""Rest everything follows."""
import numpy as np
import os
import random
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.debug_draw._debug_draw as omni_debug_draw
import omni.replicator.core as rep
from omni.isaac.core.prims import RigidPrim
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.compat.sensors.camera import Camera, PinholeCameraCfg
from omni.isaac.orbit.sensors.camera.utils import create_pointcloud_from_rgbd
from omni.isaac.orbit.utils import convert_dict_to_backend
"""
Helpers
"""
def design_scene():
"""Add prims to the scene."""
# Ground-plane
kit_utils.create_ground_plane("/World/defaultGroundPlane")
# Lights-1
prim_utils.create_prim(
"/World/Light/GreySphere",
"SphereLight",
translation=(4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (0.75, 0.75, 0.75)},
)
# Lights-2
prim_utils.create_prim(
"/World/Light/WhiteSphere",
"SphereLight",
translation=(-4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (1.0, 1.0, 1.0)},
)
# Xform to hold objects
prim_utils.create_prim("/World/Objects", "Xform")
# Random objects
for i in range(8):
# sample random position
position = np.random.rand(3) - np.asarray([0.05, 0.05, -1.0])
position *= np.asarray([1.5, 1.5, 0.5])
# create prim
prim_type = random.choice(["Cube", "Sphere", "Cylinder"])
_ = prim_utils.create_prim(
f"/World/Objects/Obj_{i:02d}",
prim_type,
translation=position,
scale=(0.25, 0.25, 0.25),
semantic_label=prim_type,
)
# add rigid properties
rigid_obj = RigidPrim(f"/World/Objects/Obj_{i:02d}", mass=5.0)
# cast to geom prim
geom_prim = getattr(UsdGeom, prim_type)(rigid_obj.prim)
# set random color
color = Gf.Vec3f(random.random(), random.random(), random.random())
geom_prim.CreateDisplayColorAttr()
geom_prim.GetDisplayColorAttr().Set([color])
"""
Main
"""
def main():
"""Runs a camera sensor from orbit."""
# Load kit helper
sim = SimulationContext(physics_dt=0.005, rendering_dt=0.005, backend="torch")
# Set main camera
set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Acquire draw interface
draw_interface = omni_debug_draw.acquire_debug_draw_interface()
# Populate scene
design_scene()
# Setup camera sensor
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors"],
usd_params=PinholeCameraCfg.UsdCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
),
)
camera = Camera(cfg=camera_cfg, device="cuda" if args_cli.gpu else "cpu")
# Spawn camera
camera.spawn("/World/CameraSensor")
# Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera")
rep_writer = rep.BasicWriter(output_dir=output_dir, frame_padding=3)
# Play simulator
sim.play()
# Initialize camera
camera.initialize()
# Set pose: There are two ways to set the pose of the camera.
# -- Option-1: Set pose using view
# camera.set_world_pose_from_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# -- Option-2: Set pose using ROS
position = [2.5, 2.5, 2.5]
orientation = [-0.17591989, 0.33985114, 0.82047325, -0.42470819]
camera.set_world_pose_ros(position, orientation)
# Simulate for a few steps
# note: This is a workaround to ensure that the textures are loaded.
# Check "Known Issues" section in the documentation for more details.
for _ in range(3):
sim.step()
# Simulate physics
while simulation_app.is_running():
# If simulation is stopped, then exit.
if sim.is_stopped():
break
# If simulation is paused, then skip.
if not sim.is_playing():
sim.step(render=not args_cli.headless)
continue
# Step simulation
sim.step()
# Update camera data
camera.update(dt=0.0)
# Print camera info
print(camera)
print("Received shape of rgb image: ", camera.data.output["rgb"].shape)
print("Received shape of depth image: ", camera.data.output["distance_to_image_plane"].shape)
print("-------------------------------")
# Save images
# note: BasicWriter only supports saving data in numpy format
rep_writer.write(convert_dict_to_backend(camera.data.output, backend="numpy"))
# Pointcloud in world frame
pointcloud_w, pointcloud_rgb = create_pointcloud_from_rgbd(
camera.data.intrinsic_matrix,
depth=camera.data.output["distance_to_image_plane"],
rgb=camera.data.output["rgb"],
position=camera.data.position,
orientation=camera.data.orientation,
normalize_rgb=True,
num_channels=4,
)
# Draw pointcloud
if not args_cli.headless and args_cli.draw:
# Convert to numpy for visualization
if not isinstance(pointcloud_w, np.ndarray):
pointcloud_w = pointcloud_w.cpu().numpy()
if not isinstance(pointcloud_rgb, np.ndarray):
pointcloud_rgb = pointcloud_rgb.cpu().numpy()
# Visualize the points
num_points = pointcloud_w.shape[0]
points_size = [1.25] * num_points
points_color = pointcloud_rgb
draw_interface.clear_points()
draw_interface.draw_points(pointcloud_w.tolist(), points_color, points_size)
if __name__ == "__main__":
# Runs the main function
main()
# Close the simulator
simulation_app.close()
......@@ -17,7 +17,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="This script demonstrates how to use the camera sensor.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--gpu", action="store_true", default=False, help="Use GPU device for camera rendering output.")
parser.add_argument("--draw", action="store_true", default=False, help="Draw the obtained pointcloud on viewport.")
......@@ -43,8 +43,8 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
from pxr import Gf, UsdGeom
import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.sensors.camera import Camera, PinholeCameraCfg
import omni.isaac.orbit.sim as sim_utils
from omni.isaac.orbit.sensors.camera import Camera, CameraCfg
from omni.isaac.orbit.utils import convert_dict_to_backend
from omni.isaac.orbit.utils.math import project_points, transform_points, unproject_depth
......@@ -55,22 +55,16 @@ Helpers
def design_scene():
"""Add prims to the scene."""
# Spawn things into stage
# Ground-plane
kit_utils.create_ground_plane("/World/defaultGroundPlane")
cfg = sim_utils.GroundPlaneCfg()
cfg.func("/World/defaultGroundPlane", cfg)
# Lights-1
prim_utils.create_prim(
"/World/Light/GreySphere",
"SphereLight",
translation=(4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (0.75, 0.75, 0.75)},
)
cfg = sim_utils.SphereLightCfg(intensity=600.0, color=(0.75, 0.75, 0.75), radius=2.5)
cfg.func("/World/Light/greyLight", cfg, translation=(4.5, 3.5, 10.0))
# Lights-2
prim_utils.create_prim(
"/World/Light/WhiteSphere",
"SphereLight",
translation=(-4.5, 3.5, 10.0),
attributes={"radius": 2.5, "intensity": 600.0, "color": (1.0, 1.0, 1.0)},
)
cfg = sim_utils.SphereLightCfg(intensity=600.0, color=(1.0, 1.0, 1.0), radius=2.5)
cfg.func("/World/Light/whiteSphere", cfg, translation=(-4.5, 3.5, 10.0))
# Xform to hold objects
prim_utils.create_prim("/World/Objects", "Xform")
# Random objects
......@@ -109,7 +103,6 @@ def main():
sim = SimulationContext(
physics_dt=0.005, rendering_dt=0.005, backend="torch", device="cuda" if args_cli.gpu else "cpu"
)
# sim = SimulationContext(physics_dt=0.005, rendering_dt=0.005, backend="numpy")
# Set main camera
set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Acquire draw interface
......@@ -118,20 +111,21 @@ def main():
# Populate scene
design_scene()
# Setup camera sensor
camera_cfg = PinholeCameraCfg(
camera_cfg = CameraCfg(
prim_path="/World/CameraSensor_.*/Cam",
update_period=0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane", "normals", "motion_vectors", "semantic_segmentation"],
usd_params=PinholeCameraCfg.UsdCameraCfg(
spawn=sim_utils.PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 1.0e5)
),
)
camera = Camera(cfg=camera_cfg)
# Spawn camera
camera.spawn("/World/CameraSensor/Cam_00")
camera.spawn("/World/CameraSensor/Cam_01")
# Manually spawn the camera because we want to be fancy
camera_cfg.spawn.func("/World/CameraSensor_00/Cam", camera_cfg.spawn)
camera_cfg.spawn.func("/World/CameraSensor_01/Cam", camera_cfg.spawn)
# Create camera
camera = Camera(cfg=camera_cfg.replace(spawn=None))
# Create replicator writer
output_dir = os.path.join(os.path.dirname(os.path.realpath(__file__)), "output", "camera")
......@@ -139,8 +133,6 @@ def main():
# Play simulator
sim.play()
# Initialize camera
camera.initialize("/World/CameraSensor/Cam_*")
# Set pose: There are two ways to set the pose of the camera.
# -- Option-1: Set pose using view
......@@ -205,7 +197,7 @@ def main():
# Pointcloud in world frame
points_3d_cam = unproject_depth(camera.data.output["distance_to_image_plane"], camera.data.intrinsic_matrices)
points_3d_world = transform_points(points_3d_cam, camera.data.position, camera.data.orientation)
points_3d_world = transform_points(points_3d_cam, camera.data.pos_w, camera.data.quat_w_ros)
# Check methods are valid
im_height, im_width = camera.image_shape
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="This script creates an empty stage in Isaac Sim.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
args_cli = parser.parse_args()
......
......@@ -38,7 +38,7 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import StaticMarker
from omni.isaac.orbit.controllers.differential_inverse_kinematics import (
DifferentialInverseKinematics,
......
......@@ -17,7 +17,9 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(
description="This script demonstrates how to use the RMPFlow controller with the simulator."
)
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--robot", type=str, default="ur10", help="Name of the robot. Options: franka_panda, ur10.")
parser.add_argument("--num_envs", type=int, default=5, help="Number of environments to spawn.")
......@@ -38,7 +40,7 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.compat.markers import StaticMarker
from omni.isaac.orbit.controllers.config.rmp_flow import FRANKA_RMPFLOW_CFG, UR10_RMPFLOW_CFG
from omni.isaac.orbit.controllers.rmp_flow import RmpFlowController
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Random agent for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
......@@ -15,7 +15,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Pick and lift state machine for lift environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Keyboard teleoperation for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.")
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Zero agent for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from RL-Games.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
......@@ -14,7 +14,7 @@ import os
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Train an RL agent with RL-Games.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Collect demonstrations for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.")
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Play policy trained using robomimic for Isaac Orbit environments.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--task", type=str, default=None, help="Name of the task.")
......
......@@ -13,7 +13,7 @@ import os
if __name__ == "__main__":
# parse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Merge multiple episodes with single trajectory into one episode.")
parser.add_argument(
"--dir", type=str, default=None, help="Path to directory that contains all single episode hdf5 files"
)
......
......@@ -25,7 +25,7 @@ def check_group(f, num: int):
if __name__ == "__main__":
# parse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Check structure of hdf5 file.")
parser.add_argument("file", type=str, default=None, help="The path to HDF5 file to analyze.")
args_cli = parser.parse_args()
......
......@@ -13,7 +13,7 @@ import argparse
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from RSL-RL.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
......@@ -14,7 +14,7 @@ import os
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Train an RL agent with RSL-RL.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
......@@ -14,7 +14,7 @@ import numpy as np
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from Stable-Baselines3.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
......@@ -15,7 +15,7 @@ import os
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Train an RL agent with Stable-Baselines3.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
......@@ -19,7 +19,7 @@ import os
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Play a checkpoint of an RL agent from skrl.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--cpu", action="store_true", default=False, help="Use CPU pipeline.")
parser.add_argument("--num_envs", type=int, default=None, help="Number of environments to simulate.")
......
......@@ -19,7 +19,7 @@ import os
from omni.isaac.orbit.app import AppLauncher
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Train an RL agent with skrl.")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--video", action="store_true", default=False, help="Record videos during training.")
parser.add_argument("--video_length", type=int, default=200, help="Length of the recorded video (in steps).")
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment