Unverified Commit e682605e authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Removes `compat` submodule from orbit (#455)

# Description

This MR removes `compat` submodule since we don't use/need it anymore.

## Type of change

- Breaking change (fix or feature that would cause existing
functionality to not work as expected)

## 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
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [x] I have run all the tests with `./orbit.sh --test` and they pass
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent cb78f892
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.13.0"
version = "0.13.1"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.13.1 (2024-03-14)
~~~~~~~~~~~~~~~~~~~
Removed
^^^^^^^
* Removed the :mod:`omni.isaac.orbit.compat` module. This module was used to provide compatibility
with older versions of Isaac Sim. It is no longer needed since we have most of the functionality
absorbed into the main classes.
0.13.0 (2024-03-12)
~~~~~~~~~~~~~~~~~~~
......
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Sub-package containing compatibility code with previous release of Orbit.
.. note::
This package is not part of the public API and may be removed in future releases.
"""
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
This submodule provides marker utilities for simplifying creation of UI elements in the GUI.
Currently, the module provides two classes:
* :class:`StaticMarker` for creating a group of markers from a single USD file.
* :class:`PointMarker` for creating a group of spheres.
.. note::
For some simple usecases, it may be sufficient to use the debug drawing utilities from Isaac Sim.
The debug drawing API is available in the `omni.isaac.debug_drawing`_ module. It allows drawing of
points and splines efficiently on the UI.
.. _omni.isaac.debug_drawing: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/ext_omni_isaac_debug_drawing.html
"""
from .point_marker import PointMarker
from .static_marker import StaticMarker
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""A class to coordinate groups of visual markers (loaded from USD)."""
from __future__ import annotations
import numpy as np
import torch
from collections.abc import Sequence
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
from pxr import Gf, UsdGeom
class PointMarker:
"""A class to coordinate groups of visual sphere markers for goal-conditioned tasks.
This class allows visualization of multiple spheres. These can be used to represent a
goal-conditioned task. For instance, if a robot is performing a task of reaching a target, the
class can be used to display a red sphere when the target is far away and a green sphere when
the target is achieved. Otherwise, the class can be used to display spheres, for example, to
mark contact points.
The class uses `UsdGeom.PointInstancer`_ for efficient handling of multiple markers in the stage.
It creates two spherical markers of different colors. Based on the indices provided the referenced
marker is activated:
- :obj:`0` corresponds to unachieved target (red sphere).
- :obj:`1` corresponds to achieved target (green sphere).
Usage:
To create 24 point target markers of radius 0.2 and show them as achieved targets:
.. code-block:: python
from omni.isaac.orbit.compat.markers import PointMarker
# create a point marker
marker = PointMarker("/World/Visuals/goal", 24, radius=0.2)
# set position of the marker
marker_positions = np.random.uniform(-1.0, 1.0, (24, 3))
marker.set_world_poses(marker_positions)
# set status of the marker to show achieved targets
marker.set_status([1] * 24)
.. _UsdGeom.PointInstancer: https://graphics.pixar.com/usd/dev/api/class_usd_geom_point_instancer.html
"""
def __init__(self, prim_path: str, count: int, radius: float = 1.0):
"""Initialize the class.
Args:
prim_path: The prim path where the PointInstancer will be created.
count: The number of marker duplicates to create.
radius: The radius of the sphere. Defaults to 1.0.
Raises:
ValueError: When a prim already exists at the :obj:`prim_path` and it is not a :class:`UsdGeom.PointInstancer`.
"""
# check inputs
stage = stage_utils.get_current_stage()
# -- prim path
if prim_utils.is_prim_path_valid(prim_path):
prim = prim_utils.get_prim_at_path(prim_path)
if not prim.IsA(UsdGeom.PointInstancer):
raise ValueError(f"The prim at path {prim_path} cannot be parsed as a `PointInstancer` object")
self._instancer_manager = UsdGeom.PointInstancer(prim)
else:
self._instancer_manager = UsdGeom.PointInstancer.Define(stage, prim_path)
# store inputs
self.prim_path = prim_path
self.count = count
self._radius = radius
# create manager for handling instancing of frame markers
self._instancer_manager = UsdGeom.PointInstancer.Define(stage, prim_path)
# create a child prim for the marker
# -- target not achieved
prim = prim_utils.create_prim(f"{prim_path}/target_far", "Sphere", attributes={"radius": self._radius})
geom = UsdGeom.Sphere(prim)
geom.GetDisplayColorAttr().Set([(1.0, 0.0, 0.0)])
# -- target achieved
prim = prim_utils.create_prim(f"{prim_path}/target_close", "Sphere", attributes={"radius": self._radius})
geom = UsdGeom.Sphere(prim)
geom.GetDisplayColorAttr().Set([(0.0, 1.0, 0.0)])
# -- target invisible
prim = prim_utils.create_prim(f"{prim_path}/target_invisible", "Sphere", attributes={"radius": self._radius})
geom = UsdGeom.Sphere(prim)
geom.GetDisplayColorAttr().Set([(0.0, 0.0, 1.0)])
prim_utils.set_prim_visibility(prim, visible=False)
# add child reference to point instancer
relation_manager = self._instancer_manager.GetPrototypesRel()
relation_manager.AddTarget(f"{prim_path}/target_far") # target index: 0
relation_manager.AddTarget(f"{prim_path}/target_close") # target index: 1
relation_manager.AddTarget(f"{prim_path}/target_invisible") # target index: 2
# buffers for storing data in pixar Gf format
# FUTURE: Make them very far away from the scene?
self._proto_indices = [0] * self.count
self._gf_positions = [Gf.Vec3f() for _ in range(self.count)]
self._gf_orientations = [Gf.Quath() for _ in range(self.count)]
# FUTURE: add option to set scales
# specify that all initial prims are related to same geometry
self._instancer_manager.GetProtoIndicesAttr().Set(self._proto_indices)
# set initial positions of the targets
self._instancer_manager.GetPositionsAttr().Set(self._gf_positions)
self._instancer_manager.GetOrientationsAttr().Set(self._gf_orientations)
def set_visibility(self, visible: bool):
"""Sets the visibility of the markers.
The method does this through the USD API.
Args:
visible: flag to set the visibility.
"""
imageable = UsdGeom.Imageable(self._instancer_manager)
if visible:
imageable.MakeVisible()
else:
imageable.MakeInvisible()
def set_world_poses(
self,
positions: np.ndarray | torch.Tensor | None = None,
orientations: np.ndarray | torch.Tensor | None = None,
indices: Sequence[int] | None = None,
):
"""Update marker poses in the simulation world frame.
Args:
positions:
Positions in the world frame. Shape is (M, 3). Defaults to None, which means left unchanged.
orientations:
Quaternion orientations (w, x, y, z) in the world frame of the prims. Shape is (M, 4).
Defaults to None, which means left unchanged.
indices: Indices to specify which alter poses.
Shape is (M,), where M <= total number of markers. Defaults to None (i.e: all markers).
"""
# resolve inputs
if positions is not None:
positions = positions.tolist()
if orientations is not None:
orientations = orientations.tolist()
if indices is None:
indices = range(self.count)
# change marker locations
for i, marker_index in enumerate(indices):
if positions is not None:
self._gf_positions[marker_index][:] = positions[i]
if orientations is not None:
self._gf_orientations[marker_index].SetReal(orientations[i][0])
self._gf_orientations[marker_index].SetImaginary(orientations[i][1:])
# apply to instance manager
self._instancer_manager.GetPositionsAttr().Set(self._gf_positions)
self._instancer_manager.GetOrientationsAttr().Set(self._gf_orientations)
def set_status(self, status: list[int] | np.ndarray | torch.Tensor, indices: Sequence[int] | None = None):
"""Updates the marker activated by the instance manager.
Args:
status: Decides which prototype marker to visualize. Shape is (M)
indices: Indices to specify which alter poses.
Shape is (M,), where M <= total number of markers. Defaults to None (i.e: all markers).
"""
# default values
if indices is None:
indices = range(self.count)
# resolve input
if status is not list:
proto_indices = status.tolist()
else:
proto_indices = status
# change marker locations
for i, marker_index in enumerate(indices):
self._proto_indices[marker_index] = int(proto_indices[i])
# apply to instance manager
self._instancer_manager.GetProtoIndicesAttr().Set(self._proto_indices)
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""A class to coordinate groups of visual markers (loaded from USD)."""
from __future__ import annotations
import numpy as np
import torch
from collections.abc import Sequence
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
from omni.isaac.core.materials import PreviewSurface
from omni.isaac.core.prims import GeometryPrim
from pxr import Gf, UsdGeom
import omni.isaac.orbit.compat.utils.kit as kit_utils
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR, check_file_path
class StaticMarker:
"""A class to coordinate groups of visual markers (loaded from USD).
This class allows visualization of different UI elements in the scene, such as points and frames.
The class uses `UsdGeom.PointInstancer`_ for efficient handling of the element in the stage
via instancing of the marker.
Usage:
To create 24 default frame markers with a scale of 0.5:
.. code-block:: python
from omni.isaac.orbit.compat.markers import StaticMarker
# create a static marker
marker = StaticMarker("/World/Visuals/frames", 24, scale=(0.5, 0.5, 0.5))
# set position of the marker
marker_positions = np.random.uniform(-1.0, 1.0, (24, 3))
marker.set_world_poses(marker_positions)
.. _UsdGeom.PointInstancer: https://graphics.pixar.com/usd/dev/api/class_usd_geom_point_instancer.html
"""
def __init__(
self,
prim_path: str,
count: int,
usd_path: str | None = None,
scale: tuple[float, float, float] = (1.0, 1.0, 1.0),
color: tuple[float, float, float] | None = None,
):
"""Initialize the class.
When the class is initialized, the :class:`UsdGeom.PointInstancer` is created into the stage
and the marker prim is registered into it.
Args:
prim_path: The prim path where the PointInstancer will be created.
count: The number of marker duplicates to create.
usd_path: The USD file path to the marker. Defaults to the USD path for the RGB frame axis marker.
scale: The scale of the marker. Defaults to (1.0, 1.0, 1.0).
color: The color of the marker. If provided, it overrides the existing color on all the
prims of the marker. Defaults to None.
Raises:
ValueError: When a prim already exists at the :obj:`prim_path` and it is not a
:class:`UsdGeom.PointInstancer`.
FileNotFoundError: When the USD file at :obj:`usd_path` does not exist.
"""
# resolve default markers in the UI elements
# -- USD path
if usd_path is None:
usd_path = f"{ISAAC_NUCLEUS_DIR}/Props/UIElements/frame_prim.usd"
else:
if not check_file_path(usd_path):
raise FileNotFoundError(f"USD file for the marker not found at: {usd_path}")
# -- prim path
stage = stage_utils.get_current_stage()
if prim_utils.is_prim_path_valid(prim_path):
# retrieve prim if it exists
prim = prim_utils.get_prim_at_path(prim_path)
if not prim.IsA(UsdGeom.PointInstancer):
raise ValueError(f"The prim at path {prim_path} cannot be parsed as a `PointInstancer` object")
self._instancer_manager = UsdGeom.PointInstancer(prim)
else:
# create a new prim
self._instancer_manager = UsdGeom.PointInstancer.Define(stage, prim_path)
# store inputs
self.prim_path = prim_path
self.count = count
self._usd_path = usd_path
# create manager for handling instancing of frame markers
self._instancer_manager = UsdGeom.PointInstancer.Define(stage, prim_path)
# create a child prim for the marker
prim_utils.create_prim(f"{prim_path}/marker", usd_path=self._usd_path)
# disable any physics on the marker
# FIXME: Also support disabling rigid body properties on the marker.
# Currently, it is not possible on GPU pipeline.
# kit_utils.set_nested_rigid_body_properties(f"{prim_path}/marker", rigid_body_enabled=False)
kit_utils.set_nested_collision_properties(f"{prim_path}/marker", collision_enabled=False)
# apply material to marker
if color is not None:
prim = GeometryPrim(f"{prim_path}/marker")
material = PreviewSurface(f"{prim_path}/markerColor", color=np.asarray(color))
prim.apply_visual_material(material, weaker_than_descendants=False)
# add child reference to point instancer
# FUTURE: Add support for multiple markers in the same instance manager?
relation_manager = self._instancer_manager.GetPrototypesRel()
relation_manager.AddTarget(f"{prim_path}/marker") # target index: 0
# buffers for storing data in pixar Gf format
# FUTURE: Make them very far away from the scene?
self._gf_positions = [Gf.Vec3f() for _ in range(self.count)]
self._gf_orientations = [Gf.Quath() for _ in range(self.count)]
self._gf_scales = [Gf.Vec3f(*tuple(scale)) for _ in range(self.count)]
# specify that all vis prims are related to same geometry
self._instancer_manager.GetProtoIndicesAttr().Set([0] * self.count)
# set initial positions of the targets
self._instancer_manager.GetScalesAttr().Set(self._gf_scales)
self._instancer_manager.GetPositionsAttr().Set(self._gf_positions)
self._instancer_manager.GetOrientationsAttr().Set(self._gf_orientations)
def set_visibility(self, visible: bool):
"""Sets the visibility of the markers.
The method does this through the USD API.
Args:
visible: flag to set the visibility.
"""
imageable = UsdGeom.Imageable(self._instancer_manager)
if visible:
imageable.MakeVisible()
else:
imageable.MakeInvisible()
def set_world_poses(
self,
positions: np.ndarray | torch.Tensor | None = None,
orientations: np.ndarray | torch.Tensor | None = None,
indices: Sequence[int] | None = None,
):
"""Update marker poses in the simulation world frame.
Args:
positions: Positions in the world frame. Shape is (M, 3). Defaults to None, which means left unchanged.
orientations: Quaternion orientations (w, x, y, z) in the world frame of the prims. Shape is (M, 4).
Defaults to None, which means left unchanged.
indices: Indices to specify which alter poses. Shape is (M,) where M <= total number of markers.
Defaults to None (i.e: all markers).
"""
# resolve inputs
if positions is not None:
positions = positions.tolist()
if orientations is not None:
orientations = orientations.tolist()
if indices is None:
indices = range(self.count)
# change marker locations
for i, marker_index in enumerate(indices):
if positions is not None:
self._gf_positions[marker_index][:] = positions[i]
if orientations is not None:
self._gf_orientations[marker_index].SetReal(orientations[i][0])
self._gf_orientations[marker_index].SetImaginary(orientations[i][1:])
# apply to instance manager
self._instancer_manager.GetPositionsAttr().Set(self._gf_positions)
self._instancer_manager.GetOrientationsAttr().Set(self._gf_orientations)
def set_scales(self, scales: np.ndarray | torch.Tensor, indices: Sequence[int] | None = None):
"""Update marker poses in the simulation world frame.
Args:
scales: Scale applied before any rotation is applied. Shape is (M, 3).
indices: Indices to specify which alter poses.
Shape is (M,), where M <= total number of markers. Defaults to None (i.e: all markers).
"""
# default arguments
if indices is None:
indices = range(self.count)
# resolve inputs
scales = scales.tolist()
# change marker locations
for i, marker_index in enumerate(indices):
self._gf_scales[marker_index][:] = scales[i]
# apply to instance manager
self._instancer_manager.GetScalesAttr().Set(self._gf_scales)
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
Camera wrapper around USD camera prim to provide an interface that follows the robotics convention.
"""
from .camera import Camera, CameraData
from .camera_cfg import FisheyeCameraCfg, PinholeCameraCfg
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Camera class in Omniverse workflows."""
from __future__ import annotations
import builtins
import math
import numpy as np
import scipy.spatial.transform as tf
from collections.abc import Sequence
from dataclasses import dataclass
from typing import Any
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
import omni.replicator.core as rep
import omni.usd
from omni.isaac.core.prims import XFormPrim
from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.rotations import gf_quat_to_np_array
from pxr import Gf, Sdf, Usd, UsdGeom
from omni.isaac.orbit.utils import class_to_dict, to_camel_case
from omni.isaac.orbit.utils.math import convert_quat
from ..sensor_base import SensorBase
from .camera_cfg import FisheyeCameraCfg, PinholeCameraCfg
@dataclass
class CameraData:
"""Data container for the camera sensor."""
position: np.ndarray = None
"""Position of the sensor origin in world frame, following ROS convention."""
orientation: np.ndarray = None
"""Quaternion orientation `(w, x, y, z)` of the sensor origin in world frame, following ROS convention."""
intrinsic_matrix: np.ndarray = None
"""The intrinsic matrix for the camera."""
image_shape: tuple[int, int] = None
"""A tuple containing (height, width) of the camera sensor."""
output: dict[str, Any] = None
"""The retrieved sensor data with sensor types as key.
The format of the data is available in the `Replicator Documentation`_.
.. _Replicator Documentation: https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_replicator/annotators_details.html#annotator-output
"""
class Camera(SensorBase):
r"""The camera sensor for acquiring visual data.
This class wraps over the `UsdGeom Camera`_ for providing a consistent API for acquiring visual data.
It ensures that the camera follows the ROS convention for the coordinate system.
Summarizing from the `replicator extension`_, the following sensor types are supported:
- ``"rgb"``: A rendered color image.
- ``"distance_to_camera"``: An image containing the distance to camera optical center.
- ``"distance_to_image_plane"``: An image containing distances of 3D points from camera plane along camera's z-axis.
- ``"normals"``: An image containing the local surface normal vectors at each pixel.
- ``"motion_vectors"``: An image containing the motion vector data at each pixel.
- ``"instance_segmentation"``: The instance segmentation data.
- ``"semantic_segmentation"``: The semantic segmentation data.
- ``"bounding_box_2d_tight"``: The tight 2D bounding box data (only contains non-occluded regions).
- ``"bounding_box_2d_loose"``: The loose 2D bounding box data (contains occluded regions).
- ``"bounding_box_3d"``: The 3D view space bounding box data.
- ``"occlusion"``: The occlusion information (such as instance id, semantic id and occluded ratio).
The camera sensor supports the following projection types:
- ``"pinhole"``: Standard pinhole camera model (disables fisheye parameters).
- ``"fisheye_orthographic"``: Fisheye camera model using orthographic correction.
- ``"fisheye_equidistant"``: Fisheye camera model using equidistant correction.
- ``"fisheye_equisolid"``: Fisheye camera model using equisolid correction.
- ``"fisheye_polynomial"``: Fisheye camera model with :math:`360^{\circ}` spherical projection.
- ``"fisheye_spherical"``: Fisheye camera model with :math:`360^{\circ}` full-frame projection.
.. _replicator extension: https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_replicator/annotators_details.html#annotator-output
.. _USDGeom Camera: https://graphics.pixar.com/usd/docs/api/class_usd_geom_camera.html
"""
def __init__(self, cfg: PinholeCameraCfg | FisheyeCameraCfg, device: str = "cpu"):
"""Initializes the camera sensor.
If the ``device`` is ``"cpu"``, the output data is returned as a numpy array. If the ``device`` is
``"cuda"``, then a Warp array is returned. Note that only the valid sensor types will be moved to GPU.
Args:
cfg: The configuration parameters.
device: The device on which to receive data. Defaults to "cpu".
"""
# store inputs
self.cfg = cfg
self.device = device
# initialize base class
super().__init__(self.cfg.sensor_tick)
# change the default rendering settings
# TODO: Should this be done here or maybe inside the app config file?
rep.settings.set_render_rtx_realtime(antialiasing="FXAA")
# Xform prim for handling transforms
self._sensor_xform: XFormPrim = None
# UsdGeom Camera prim for the sensor
self._sensor_prim: UsdGeom.Camera = None
# Create empty variables for storing output data
self._data = CameraData()
self._data.output = dict.fromkeys(self.cfg.data_types, None)
# Flag to check that sensor is spawned.
self._is_spawned = False
def __str__(self) -> str:
"""Returns: A string containing information about the instance."""
# message for class
return (
f"Camera @ '{self.prim_path}': \n"
f"\tdata types : {list(self._data.output.keys())} \n"
f"\ttick rate (s): {self.sensor_tick}\n"
f"\ttimestamp (s): {self.timestamp}\n"
f"\tframe : {self.frame}\n"
f"\tshape : {self.image_shape}\n"
f"\tposition : {self._data.position} \n"
f"\torientation : {self._data.orientation} \n"
)
"""
Properties
"""
@property
def prim_path(self) -> str:
"""The path to the camera prim."""
return prim_utils.get_prim_path(self._sensor_prim)
@property
def render_product_path(self) -> str:
"""The path of the render product for the camera.
This can be used via replicator interfaces to attach to writes or external annotator registry.
"""
return self._render_product_path
@property
def data(self) -> CameraData:
"""Data related to Camera sensor."""
return self._data
@property
def image_shape(self) -> tuple[int, int]:
"""A tuple containing (height, width) of the camera sensor."""
return (self.cfg.height, self.cfg.width)
"""
Configuration
"""
def set_visibility(self, visible: bool):
"""Set visibility of the instance in the scene.
Args:
visible: Whether to make instance visible or invisible.
Raises:
RuntimeError: If the camera prim is not set. Need to call :meth:`initialize` first.
"""
# check camera prim
if self._sensor_prim is None:
raise RuntimeError("Camera prim is None. Please call 'initialize(...)' first.")
# get imageable object
imageable = UsdGeom.Imageable(self._sensor_prim)
# set visibility
if visible:
imageable.MakeVisible()
else:
imageable.MakeInvisible()
def set_intrinsic_matrix(self, matrix: np.ndarray, focal_length: float = 1.0):
"""Set parameters of the USD camera from its intrinsic matrix.
The intrinsic matrix and focal length are used to set the following parameters to the USD camera:
- ``focal_length``: The focal length of the camera.
- ``horizontal_aperture``: The horizontal aperture of the camera.
- ``vertical_aperture``: The vertical aperture of the camera.
- ``horizontal_aperture_offset``: The horizontal offset of the camera.
- ``vertical_aperture_offset``: The vertical offset of the camera.
.. warning::
Due to limitations of Omniverse camera, we need to assume that the camera is a spherical lens,
i.e. has square pixels, and the optical center is centered at the camera eye. If this assumption
is not true in the input intrinsic matrix, then the camera will not set up correctly.
Args:
intrinsic_matrix: The intrinsic matrix for the camera.
focal_length: Focal length to use when computing aperture values. Defaults to 1.0.
"""
# convert to numpy for sanity
intrinsic_matrix = np.asarray(matrix, dtype=float)
# extract parameters from matrix
f_x = intrinsic_matrix[0, 0]
c_x = intrinsic_matrix[0, 2]
f_y = intrinsic_matrix[1, 1]
c_y = intrinsic_matrix[1, 2]
# get viewport parameters
height, width = self.image_shape
height, width = float(height), float(width)
# resolve parameters for usd camera
params = {
"focal_length": focal_length,
"horizontal_aperture": width * focal_length / f_x,
"vertical_aperture": height * focal_length / f_y,
"horizontal_aperture_offset": (c_x - width / 2) / f_x,
"vertical_aperture_offset": (c_y - height / 2) / f_y,
}
# set parameters for camera
for param_name, param_value in params.items():
# convert to camel case (CC)
param_name = to_camel_case(param_name, to="CC")
# get attribute from the class
param_attr = getattr(self._sensor_prim, f"Get{param_name}Attr")
# set value
# note: We have to do it this way because the camera might be on a different layer (default cameras are on session layer),
# and this is the simplest way to set the property on the right layer.
omni.usd.utils.set_prop_val(param_attr(), param_value)
"""
Operations - Set pose.
"""
def set_world_pose_ros(self, pos: Sequence[float] = None, quat: Sequence[float] = None):
r"""Set the pose of the camera w.r.t. world frame using ROS convention.
In USD, the camera is always in **Y up** convention. This means that the camera is looking down the -Z axis
with the +Y axis pointing up , and +X axis pointing right. However, in ROS, the camera is looking down
the +Z axis with the +Y axis pointing down, and +X axis pointing right. Thus, the camera needs to be rotated
by :math:`180^{\circ}` around the X axis to follow the ROS convention.
.. math::
T_{ROS} = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & -1 & 0 & 0 \\ 0 & 0 & -1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix} T_{USD}
Args:
pos: The cartesian coordinates (in meters). Defaults to None.
quat: The quaternion orientation in (w, x, y, z). Defaults to None.
Raises:
RuntimeError: If the camera prim is not set. Need to call :meth:`initialize` method first.
"""
# check camera prim exists
if self._sensor_prim is None:
raise RuntimeError("Camera prim is None. Please call 'initialize(...)' first.")
# convert from meters to stage units
if pos is not None:
pos = np.asarray(pos)
# convert rotation matrix from ROS convention to OpenGL
if quat is not None:
rotm = tf.Rotation.from_quat(convert_quat(quat, "xyzw")).as_matrix()
rotm[:, 2] = -rotm[:, 2]
rotm[:, 1] = -rotm[:, 1]
# convert to isaac-sim convention
quat_gl = tf.Rotation.from_matrix(rotm).as_quat()
quat_gl = convert_quat(quat_gl, "wxyz")
else:
quat_gl = None
# set the pose
self._sensor_xform.set_world_pose(pos, quat_gl)
def set_world_pose_from_view(self, eye: Sequence[float], target: Sequence[float] = [0, 0, 0]):
"""Set the pose of the camera from the eye position and look-at target position.
Args:
eye: The position of the camera's eye.
target: The target location to look at. Defaults to [0, 0, 0].
Raises:
RuntimeError: If the camera prim is not set. Need to call :meth:`initialize` method first.
NotImplementedError: If the stage up-axis is not "Y" or "Z".
"""
# check camera prim exists
if self._sensor_prim is None:
raise RuntimeError("Camera prim is None. Please call 'initialize(...)' first.")
# compute camera's eye pose
eye_position = Gf.Vec3d(np.asarray(eye).tolist())
target_position = Gf.Vec3d(np.asarray(target).tolist())
# compute forward direction
forward_dir = (eye_position - target_position).GetNormalized()
# get up axis
up_axis_token = stage_utils.get_stage_up_axis()
if up_axis_token == UsdGeom.Tokens.y:
# deal with degenerate case
if forward_dir == Gf.Vec3d(0, 1, 0):
up_axis = Gf.Vec3d(0, 0, 1)
elif forward_dir == Gf.Vec3d(0, -1, 0):
up_axis = Gf.Vec3d(0, 0, -1)
else:
up_axis = Gf.Vec3d(0, 1, 0)
elif up_axis_token == UsdGeom.Tokens.z:
# deal with degenerate case
if forward_dir == Gf.Vec3d(0, 0, 1):
up_axis = Gf.Vec3d(0, 1, 0)
elif forward_dir == Gf.Vec3d(0, 0, -1):
up_axis = Gf.Vec3d(0, -1, 0)
else:
up_axis = Gf.Vec3d(0, 0, 1)
else:
raise NotImplementedError(f"This method is not supported for up-axis '{up_axis_token}'.")
# compute matrix transformation
# view matrix: camera_T_world
matrix_gf = Gf.Matrix4d(1).SetLookAt(eye_position, target_position, up_axis)
# camera position and rotation in world frame
matrix_gf = matrix_gf.GetInverse()
cam_pos = np.array(matrix_gf.ExtractTranslation())
cam_quat = gf_quat_to_np_array(matrix_gf.ExtractRotationQuat())
# set camera pose
self._sensor_xform.set_world_pose(cam_pos, cam_quat)
"""
Operations
"""
def spawn(self, parent_prim_path: str, translation: Sequence[float] = None, orientation: Sequence[float] = None):
"""Spawns the sensor into the stage.
The USD Camera prim is spawned under the parent prim at the path ``parent_prim_path`` with the provided input
translation and orientation.
Args:
parent_prim_path: The path of the parent prim to attach sensor to.
translation: The local position offset w.r.t. parent prim. Defaults to None.
orientation: The local rotation offset in (w, x, y, z) w.r.t.
parent prim. Defaults to None.
"""
# Check if sensor is already spawned
if self._is_spawned:
raise RuntimeError(f"The camera sensor instance has already been spawned at: {self.prim_path}.")
# Create sensor prim path
prim_path = stage_utils.get_next_free_path(f"{parent_prim_path}/Camera")
# Create sensor prim
self._sensor_prim = UsdGeom.Camera(prim_utils.define_prim(prim_path, "Camera"))
# Add replicator camera attributes
self._define_usd_camera_attributes()
# Set the transformation of the camera
self._sensor_xform = XFormPrim(self.prim_path)
self._sensor_xform.set_local_pose(translation, orientation)
# Set spawning to true
self._is_spawned = True
def initialize(self, cam_prim_path: str = None):
"""Initializes the sensor handles and internal buffers.
This function creates handles and registers the provided data types with the replicator registry to
be able to access the data from the sensor. It also initializes the internal buffers to store the data.
The function also allows initializing to a camera not spawned by using the :meth:`spawn` method.
For instance, cameras that already exist in the USD stage. In such cases, the USD settings present on
the camera prim is used instead of the settings passed in the configuration object.
Args:
cam_prim_path: The prim path to existing camera. Defaults to None.
has_rig: Whether the passed camera prim path is attached to a rig. Defaults to False.
Raises:
RuntimeError: When input `cam_prim_path` is None, the method defaults to using the last
camera prim path set when calling the :meth:`spawn` function. In case, the camera was not spawned
and no valid `cam_prim_path` is provided, the function throws an error.
"""
# Check that sensor has been spawned
if cam_prim_path is None:
if not self._is_spawned:
raise RuntimeError("Initialize the camera failed! Please provide a valid argument for `prim_path`.")
else:
# Get prim at path
cam_prim = prim_utils.get_prim_at_path(cam_prim_path)
# Check if prim is valid
if cam_prim.IsValid() is False:
raise RuntimeError(f"Initialize the camera failed! Invalid prim path: {cam_prim_path}.")
# Force to set active camera to input prim path
self._sensor_prim = UsdGeom.Camera(cam_prim)
self._sensor_xform = XFormPrim(cam_prim_path)
# Enable synthetic data sensors
self._render_product_path = rep.create.render_product(
self.prim_path, resolution=(self.cfg.width, self.cfg.height)
)
# Attach the sensor data types to render node
self._rep_registry: dict[str, rep.annotators.Annotator] = dict.fromkeys(self.cfg.data_types, None)
# -- iterate over each data type
for name in self.cfg.data_types:
# init params -- Checked from rep.scripts.writes_default.basic_writer.py
# note: we are verbose here to make it easier to understand the code.
# if colorize is true, the data is mapped to colors and a uint8 4 channel image is returned.
# if colorize is false, the data is returned as a uint32 image with ids as values.
if name in ["bounding_box_2d_tight", "bounding_box_2d_loose", "bounding_box_3d"]:
init_params = {"semanticTypes": self.cfg.semantic_types}
elif name in ["semantic_segmentation", "instance_segmentation"]:
init_params = {"semanticTypes": self.cfg.semantic_types, "colorize": False}
elif name in ["instance_id_segmentation"]:
init_params = {"colorize": False}
else:
init_params = None
# create annotator node
rep_annotator = rep.AnnotatorRegistry.get_annotator(name, init_params, device=self.device)
rep_annotator.attach([self._render_product_path])
# add to registry
self._rep_registry[name] = rep_annotator
# Reset internal buffers
self.reset()
# When running in standalone mode, need to render a few times to fill all the buffers
# FIXME: Check with simulation team to get rid of this. What if someone has render or other callbacks?
if builtins.ISAAC_LAUNCHED_FROM_TERMINAL is False:
# get simulation context
sim_context = SimulationContext.instance()
# render a few times
for _ in range(4):
sim_context.render()
def reset(self):
# reset the timestamp
super().reset()
# reset the buffer
self._data.position = None
self._data.orientation = None
self._data.intrinsic_matrix = self._compute_intrinsic_matrix()
self._data.image_shape = self.image_shape
self._data.output = dict.fromkeys(self._data.output, None)
def buffer(self):
"""Updates the internal buffer with the latest data from the sensor.
This function reads the intrinsic matrix and pose of the camera. It also reads the data from
the annotator registry and updates the internal buffer.
Note:
When running in standalone mode, the function renders the scene a few times to fill all the buffers.
During this time, the physics simulation is paused. This is a known issue with Isaac Sim.
"""
# -- intrinsic matrix
self._data.intrinsic_matrix = self._compute_intrinsic_matrix()
# -- pose
self._data.position, self._data.orientation = self._compute_ros_pose()
# -- read the data from annotator registry
for name in self._rep_registry:
self._data.output[name] = self._rep_registry[name].get_data()
# -- update the trigger call data (needed by replicator BasicWriter method)
self._data.output["trigger_outputs"] = {"on_time": self.frame}
"""
Private Helpers
"""
def _define_usd_camera_attributes(self):
"""Creates and sets USD camera attributes.
This function creates additional attributes on the camera prim used by Replicator.
It also sets the default values for these attributes based on the camera configuration.
"""
# camera attributes
# reference: omni.replicator.core.scripts.create.py: camera()
attribute_types = {
"cameraProjectionType": "token",
"fthetaWidth": "float",
"fthetaHeight": "float",
"fthetaCx": "float",
"fthetaCy": "float",
"fthetaMaxFov": "float",
"fthetaPolyA": "float",
"fthetaPolyB": "float",
"fthetaPolyC": "float",
"fthetaPolyD": "float",
"fthetaPolyE": "float",
}
# get camera prim
prim = prim_utils.get_prim_at_path(self.prim_path)
# create attributes
for attr_name, attr_type in attribute_types.items():
# check if attribute does not exist
if prim.GetAttribute(attr_name).Get() is None:
# create attribute based on type
if attr_type == "token":
prim.CreateAttribute(attr_name, Sdf.ValueTypeNames.Token)
elif attr_type == "float":
prim.CreateAttribute(attr_name, Sdf.ValueTypeNames.Float)
# set attribute values
# -- projection type
projection_type = to_camel_case(self.cfg.projection_type, to="cC")
prim.GetAttribute("cameraProjectionType").Set(projection_type)
# -- other attributes
for param_name, param_value in class_to_dict(self.cfg.usd_params).items():
# check if value is valid
if param_value is None:
continue
# convert to camel case (CC)
param = to_camel_case(param_name, to="cC")
# get attribute from the class
prim.GetAttribute(param).Set(param_value)
def _compute_intrinsic_matrix(self) -> np.ndarray:
"""Compute camera's matrix of intrinsic parameters.
Also called calibration matrix. This matrix works for linear depth images. We assume square pixels.
Note:
The calibration matrix projects points in the 3D scene onto an imaginary screen of the camera.
The coordinates of points on the image plane are in the homogeneous representation.
Returns:
A 3 x 3 numpy array containing the intrinsic parameters for the camera.
Raises:
RuntimeError: If the camera prim is not set. Need to call :meth:`initialize` first.
"""
# check camera prim exists
if self._sensor_prim is None:
raise RuntimeError("Camera prim is None. Please call 'initialize(...)' first.")
# get camera parameters
focal_length = self._sensor_prim.GetFocalLengthAttr().Get()
horiz_aperture = self._sensor_prim.GetHorizontalApertureAttr().Get()
# get viewport parameters
height, width = self.image_shape
# calculate the field of view
fov = 2 * math.atan(horiz_aperture / (2 * focal_length))
# calculate the focal length in pixels
focal_px = width * 0.5 / math.tan(fov / 2)
# create intrinsic matrix for depth linear
a = focal_px
b = width * 0.5
c = focal_px
d = height * 0.5
# return the matrix
return np.array([[a, 0, b], [0, c, d], [0, 0, 1]], dtype=float)
def _compute_ros_pose(self) -> tuple[np.ndarray, np.ndarray]:
"""Computes the pose of the camera in the world frame with ROS convention.
This methods uses the ROS convention to resolve the input pose. In this convention,
we assume that the camera front-axis is +Z-axis and up-axis is -Y-axis.
Returns:
A tuple of the position (in meters) and quaternion (w, x, y, z).
"""
# get camera's location in world space
prim_tf = self._sensor_prim.ComputeLocalToWorldTransform(Usd.TimeCode.Default())
# GfVec datatypes are row vectors that post-multiply matrices to effect transformations,
# which implies, for example, that it is the fourth row of a GfMatrix4d that specifies
# the translation of the transformation. Thus, we take transpose here to make it post multiply.
prim_tf = np.transpose(prim_tf)
# extract the position (convert it to SI units-- assumed that stage units is 1.0)
pos = prim_tf[0:3, 3]
# extract rotation
# Note: OpenGL camera transform is such that camera faces along -z axis and +y is up.
# In robotics, we need to rotate it such that the camera is along +z axis and -y is up.
cam_rotm = prim_tf[0:3, 0:3]
# make +z forward
cam_rotm[:, 2] = -cam_rotm[:, 2]
# make +y down
cam_rotm[:, 1] = -cam_rotm[:, 1]
# convert rotation to quaternion
quat = tf.Rotation.from_matrix(cam_rotm).as_quat()
return pos, convert_quat(quat, "wxyz")
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the camera sensor."""
from __future__ import annotations
from dataclasses import MISSING
from omni.isaac.orbit.utils import configclass
@configclass
class PinholeCameraCfg:
"""Configuration for a pinhole camera sensor."""
@configclass
class UsdCameraCfg:
"""USD related configuration of the sensor.
The parameter is kept default from USD if it is set to None. This includes the default
parameters (in case the sensor is created) or the ones set by the user (in case the sensor is
loaded from existing USD stage).
Reference:
* https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_replicator/annotators_details.html
* https://graphics.pixar.com/usd/docs/api/class_usd_geom_camera.html
"""
clipping_range: tuple[float, float] = None
"""Near and far clipping distances (in stage units)."""
focal_length: float = None
"""Perspective focal length (in mm). Longer lens lengths narrower FOV, shorter lens lengths wider FOV."""
focus_distance: float = None
"""Distance from the camera to the focus plane (in stage units).
The distance at which perfect sharpness is achieved.
"""
f_stop: float = None
"""Lens aperture. Defaults to 0.0, which turns off focusing.
Controls Distance Blurring. Lower Numbers decrease focus range, larger numbers increase it.
"""
horizontal_aperture: float = None
"""Horizontal aperture (in mm). Emulates sensor/film width on a camera."""
horizontal_aperture_offset: float = None
"""Offsets Resolution/Film gate horizontally."""
vertical_aperture_offset: float = None
"""Offsets Resolution/Film gate vertically."""
sensor_tick: float = 0.0
"""Simulation seconds between sensor buffers. Defaults to 0.0."""
data_types: list[str] = ["rgb"]
"""List of sensor names/types to enable for the camera. Defaults to ["rgb"]."""
width: int = MISSING
"""Width of the image in pixels."""
height: int = MISSING
"""Height of the image in pixels."""
semantic_types: list[str] = ["class"]
"""List of allowed semantic types the types. Defaults to ["class"].
For example, if semantic types is [“class”], only the bounding boxes for prims with semantics of
type “class” will be retrieved.
More information available at:
https://docs.omniverse.nvidia.com/app_code/prod_extensions/ext_replicator/semantic_schema_editor.html
"""
projection_type: str = "pinhole"
"""Type of projection to use for the camera. Defaults to "pinhole"."""
usd_params: UsdCameraCfg = UsdCameraCfg()
"""Parameters for setting USD camera settings."""
@configclass
class FisheyeCameraCfg(PinholeCameraCfg):
"""Configuration for a fisheye camera sensor."""
@configclass
class UsdCameraCfg(PinholeCameraCfg.UsdCameraCfg):
"""USD related configuration of the sensor for the fisheye model."""
fisheye_nominal_width: float = None
"""Nominal width of fisheye lens model."""
fisheye_nominal_height: float = None
"""Nominal height of fisheye lens model."""
fisheye_optical_centre_x: float = None
"""Horizontal optical centre position of fisheye lens model."""
fisheye_optical_centre_y: float = None
"""Vertical optical centre position of fisheye lens model."""
fisheye_max_fov: float = None
"""Maximum field of view of fisheye lens model."""
fisheye_polynomial_a: float = None
"""First component of fisheye polynomial."""
fisheye_polynomial_b: float = None
"""Second component of fisheye polynomial."""
fisheye_polynomial_c: float = None
"""Third component of fisheye polynomial."""
fisheye_polynomial_d: float = None
"""Fourth component of fisheye polynomial."""
fisheye_polynomial_e: float = None
"""Fifth component of fisheye polynomial."""
projection_type: str = "fisheye_polynomial"
"""Type of projection to use for the camera. Defaults to "fisheye_polynomial"."""
usd_params: UsdCameraCfg = UsdCameraCfg()
"""Parameters for setting USD camera settings."""
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
Height-scanner based on ray-casting operations using PhysX ray-caster.
"""
from .height_scanner import HeightScanner, HeightScannerData
from .height_scanner_cfg import HeightScannerCfg
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import numpy as np
import scipy.spatial.transform as tf
from collections.abc import Sequence
from dataclasses import dataclass
import omni
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
from omni.isaac.core.prims import XFormPrim
from omni.isaac.orbit.utils.math import convert_quat
from ..sensor_base import SensorBase
from .height_scanner_cfg import HeightScannerCfg
from .height_scanner_marker import HeightScannerMarker
@dataclass
class HeightScannerData:
"""Data container for the height-scanner sensor."""
position: np.ndarray = None
"""Position of the sensor origin in world frame."""
orientation: np.ndarray = None
"""Orientation of the sensor origin in quaternion (w, x, y, z) in world frame."""
hit_points: np.ndarray = None
"""The end point locations of ray-casted rays. Shape is (N, 3), where N is
the number of scan points."""
hit_distance: np.ndarray = None
"""The ray-cast travel distance from query point. Shape is (N,), where N is
the number of scan points."""
hit_status: np.ndarray = None
"""Whether the ray hit an object or not. Shape is (N,), where N is
the number of scan points.
It is set to ``1`` if the ray hit an object, and ``0`` otherwise.
"""
class HeightScanner(SensorBase):
"""A two-dimensional height-map scan sensor.
A local map is often required to plan a robot's motion over a limited time horizon. For mobile systems,
often we care about the terrain for locomotion. The height-map, also called elevation map, simplifies the
terrain as a two-dimensional surface. Each grid-cell represents the height of the terrain.
Unlike algorithms which fuse depth measurements to create an elevation map :cite:p:`frankhauser2018probabilistic`,
in this method we directly use the PhysX API for ray-casting and query the height of the terrain from a set
of query scan points. These points represent the location of the grid cells.
The height-scanner uses PhysX for ray-casting to collision bodies. To prevent the casting to certain prims
in the scene (such as the robot on which height-scanner is present), one needs to provide the names of the
prims to not check collision with as a part of the dictionary config.
The scanner offset :math:`(x_o, y_o, z_o)` is the offset of the sensor from the frame it is attached to.
During the :meth:`update` or :meth:`buffer`, the pose of the mounted frame needs to be provided.
If visualization is enabled, rays that have a hit are displayed in red, while a miss is displayed in blue.
During a miss, the point's distance is set to the maximum ray-casting distance.
"""
def __init__(self, cfg: HeightScannerCfg):
"""Initializes the scanner object.
Args:
cfg: The configuration parameters.
"""
# TODO: Use generic range sensor from Isaac Sim?
# Reference: https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/ext_omni_isaac_range_sensor.html#isaac-sim-generic-range-sensor-example
# store inputs
self.cfg = cfg
# initialize base class
super().__init__(self.cfg.sensor_tick)
# Points to query ray-casting from
self._scan_points = np.asarray(self.cfg.points)
# If points are 2D, add dimension along z (z=0 relative to the sensor frame)
if self._scan_points.shape[1] == 2:
self._scan_points = np.pad(self._scan_points, [(0, 0), (0, 1)], constant_values=0)
# Flag to check that sensor is spawned.
self._is_spawned = False
# Whether to visualize the scanner points. Defaults to False.
self._visualize = False
# Xform prim for the sensor rig
self._sensor_xform: XFormPrim = None
# Create empty variables for storing output data
self._data = HeightScannerData()
def __str__(self) -> str:
"""Returns: A string containing information about the instance."""
# message for class
return (
f"Height Scanner @ '{self.prim_path}': \n"
f"\ttick rate (s) : {self.sensor_tick}\n"
f"\ttimestamp (s) : {self.timestamp}\n"
f"\tframe : {self.frame}\n"
f"\tposition : {self.data.position}\n"
f"\torientation : {self.data.orientation}\n"
f"\t# of hits : {np.sum(self.data.hit_status)} / {self._scan_points[0]}\n"
)
"""
Properties
"""
@property
def prim_path(self) -> str:
"""The path to the height-map sensor."""
return self._sensor_xform.prim_path
@property
def data(self) -> HeightScannerData:
"""Data related to height scanner."""
return self._data
"""
Helpers
"""
def set_visibility(self, visible: bool):
"""Enables drawing of the scan points in the viewport.
Args:
visible: Whether to draw scan points or not.
"""
# copy argument
self._visualize = visible
# set visibility
self._height_scanner_vis.set_visibility(visible)
def set_filter_prims(self, names: list[str]):
"""Set the names of prims to ignore ray-casting collisions with.
If None is passed into argument, then no filtering is performed.
Args:
names: A list of prim names to ignore ray-cast collisions with.
"""
# default
if names is None:
self.cfg.filter_prims = list()
else:
# set into the class
self.cfg.filter_prims = names
"""
Operations
"""
def spawn(self, parent_prim_path: str): # noqa: D102
# Check if sensor is already spawned
if self._is_spawned:
raise RuntimeError(f"The height scanner sensor instance has already been spawned at: {self.prim_path}.")
# Create sensor prim path
prim_path = stage_utils.get_next_free_path(f"{parent_prim_path}/HeightScan_Xform")
# Create the sensor prim
prim_utils.create_prim(prim_path, "XForm")
self._sensor_xform = XFormPrim(prim_path, translation=self.cfg.offset)
# Create visualization marker
# TODO: Move this inside the height-scan prim to make it cleaner?
vis_prim_path = stage_utils.get_next_free_path("/World/Visuals/HeightScan")
self._height_scanner_vis = HeightScannerMarker(vis_prim_path, count=self._scan_points.shape[0], radius=0.02)
# Set spawning to true
self._is_spawned = True
def initialize(self): # noqa: D102
# Check that sensor has been spawned
if not self._is_spawned:
raise RuntimeError("Height scanner sensor must be spawned first. Please call `spawn(...)`.")
# Initialize Xform class
self._sensor_xform.initialize()
# Acquire physx ray-casting interface
self._physx_query_interface = omni.physx.get_physx_scene_query_interface()
# Since height scanner is fictitious sensor, we have no schema config to set in this case.
# Initialize buffers
self.reset()
def reset(self): # noqa: D102
# reset the timestamp
super().reset()
# reset the buffer
self._data.hit_points = np.empty(shape=(self._scan_points.shape))
self._data.hit_distance = np.empty(shape=(self._scan_points.shape[0]))
self._data.hit_status = np.zeros(shape=(self._scan_points.shape[0]))
self._data.position = None
self._data.orientation = None
def update(self, dt: float, pos: Sequence[float], quat: Sequence[float]):
"""Updates the buffers at sensor frequency.
Args:
dt: The simulation time-step.
pos: Position of the frame to which the sensor is attached.
quat: Quaternion (w, x, y, z) of the frame to which the sensor is attached.
"""
super().update(dt, pos, quat)
def buffer(self, pos: Sequence[float], quat: Sequence[float]):
"""Fills the buffers of the sensor data.
This function uses the input position and orientation to compute the ray-casting queries
and fill the buffers. If a collision is detected, then the hit distance is stored in the buffer.
Otherwise, the hit distance is set to the maximum value specified in the configuration.
Args:
pos: Position of the frame to which the sensor is attached.
quat: Quaternion (w, x, y, z) of the frame to which the sensor is attached.
"""
# convert to numpy for sanity
pos = np.asarray(pos)
quat = np.asarray(quat)
# account for the offset of the sensor
self._data.position, self._data.orientation = (pos + self.cfg.offset, quat)
# construct 3D rotation matrix for grid points
# TODO: Check if this is the most generic case. It ignores the base pitch and roll.
tf_rot = tf.Rotation.from_quat(convert_quat(self.data.orientation, "xyzw"))
rpy = tf_rot.as_euler("xyz", degrees=False)
rpy[:2] = 0
rotation = tf.Rotation.from_euler("xyz", rpy).as_matrix()
# transform the scan points to world frame
world_scan_points = np.matmul(rotation, self._scan_points.T).T + self.data.position
# iterate over all the points and query ray-caster
for i in range(world_scan_points.shape[0]):
# set current query info to empty
self._query_info = None
# perform ray-cast to get distance of a point along (0, 0, -1)
self._physx_query_interface.raycast_all(
tuple(world_scan_points[i]),
self.cfg.direction,
self.cfg.max_distance,
self._hit_report_callback,
)
# check if hit happened based on query info and add to data
if self._query_info is not None:
self._data.hit_status[i] = 1
self._data.hit_distance[i] = self._query_info.distance
else:
self._data.hit_status[i] = 0
self._data.hit_distance[i] = self.cfg.max_distance
# add ray-end point (in world frame) to data
self._data.hit_points[i] = world_scan_points[i] + np.array(self.cfg.direction) * self._data.hit_distance[i]
# visualize the prim
if self._visualize:
self._height_scanner_vis.set_status(status=self._data.hit_status)
self._height_scanner_vis.set_world_poses(positions=self._data.hit_points)
"""
Private helpers
"""
def _hit_report_callback(self, hit) -> bool:
"""A PhysX callback to filter out hit-reports that are on the collision bodies.
Returns:
If True, continue casting the ray. Otherwise, stop and report the result.
"""
# unset the query info
self._query_info = None
# get ray's current contact rigid body
current_hit_body = hit.rigid_body
# check if the collision body is in the filtering list
if current_hit_body in self.cfg.filter_prims:
# continue casting the ray
return True
else:
# set the hit information
self._query_info = hit
return False
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the height scanner sensor."""
from __future__ import annotations
from dataclasses import MISSING
from omni.isaac.orbit.utils import configclass
@configclass
class HeightScannerCfg:
"""Configuration for the height-scanner sensor."""
sensor_tick: float = 0.0
"""Simulation seconds between sensor buffers. Defaults to 0.0."""
points: list = MISSING
"""The 2D scan points to query ray-casting from. Results are reported in this order."""
offset: tuple[float, float, float] = (0.0, 0.0, 0.0)
"""The offset from the frame the sensor is attached to. Defaults to (0.0, 0.0, 0.0)."""
direction: tuple[float, float, float] = (0.0, 0.0, -1.0)
"""Unit direction for the scanner ray-casting. Defaults to (0.0, 0.0, -1.0)."""
max_distance: float = 100.0
"""Maximum distance from the sensor to ray cast to. Defaults to 100.0."""
filter_prims: list[str] = list()
"""A list of prim names to ignore ray-cast collisions with. Defaults to empty list."""
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Helper class to handle visual sphere markers to show ray-casting of height scanner."""
from __future__ import annotations
import numpy as np
import torch
from collections.abc import Sequence
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
from pxr import Gf, UsdGeom
class HeightScannerMarker:
"""Helper class to handle visual sphere markers to show ray-casting of height scanner.
The class uses :class:`UsdGeom.PointInstancer` for efficient handling of multiple markers in the stage.
It creates two spherical markers of different colors. Based on the indices provided the referenced
marker is activated.
The status marker (proto-indices) of the point instancer is used to store the following information:
- :obj:`0` -> ray miss (blue sphere).
- :obj:`1` -> successful ray hit (red sphere).
- :obj:`2` -> invisible ray (disabled visualization)
"""
def __init__(self, prim_path: str, count: int, radius: float = 1.0) -> None:
"""Initialize the class.
Args:
prim_path: The prim path of the point instancer.
count: The number of markers to create.
radius: The radius of the spherical markers. Defaults to 1.0.
Raises:
ValueError: When a prim at the given path exists but is not a valid point instancer.
"""
# check inputs
stage = stage_utils.get_current_stage()
# -- prim path
if prim_utils.is_prim_path_valid(prim_path):
prim = prim_utils.get_prim_at_path(prim_path)
if not prim.IsA(UsdGeom.PointInstancer):
raise ValueError(f"The prim at path {prim_path} cannot be parsed as a `PointInstancer` object")
self._instancer_manager = UsdGeom.PointInstancer(prim)
else:
self._instancer_manager = UsdGeom.PointInstancer.Define(stage, prim_path)
# store inputs
self.prim_path = prim_path
self.count = count
self._radius = radius
# create manager for handling instancing of frame markers
self._instancer_manager = UsdGeom.PointInstancer.Define(stage, prim_path)
# TODO: Make this generic marker for all and put inside the `omni.isaac.orbit.marker` directory.
# create a child prim for the marker
# -- target missed
prim = prim_utils.create_prim(f"{prim_path}/point_miss", "Sphere", attributes={"radius": self._radius})
geom = UsdGeom.Sphere(prim)
geom.GetDisplayColorAttr().Set([(0.0, 0.0, 1.0)])
# -- target achieved
prim = prim_utils.create_prim(f"{prim_path}/point_hit", "Sphere", attributes={"radius": self._radius})
geom = UsdGeom.Sphere(prim)
geom.GetDisplayColorAttr().Set([(1.0, 0.0, 0.0)])
# -- target invisible
prim = prim_utils.create_prim(f"{prim_path}/point_invisible", "Sphere", attributes={"radius": self._radius})
geom = UsdGeom.Sphere(prim)
geom.GetDisplayColorAttr().Set([(0.0, 0.0, 1.0)])
prim_utils.set_prim_visibility(prim, visible=False)
# add child reference to point instancer
relation_manager = self._instancer_manager.GetPrototypesRel()
relation_manager.AddTarget(f"{prim_path}/point_miss") # target index: 0
relation_manager.AddTarget(f"{prim_path}/point_hit") # target index: 1
relation_manager.AddTarget(f"{prim_path}/point_invisible") # target index: 2
# buffers for storing data in pixar Gf format
# TODO: Make them very far away from the scene?
self._proto_indices = [2] * self.count
self._gf_positions = [Gf.Vec3f(0.0, 0.0, -10.0) for _ in range(self.count)]
self._gf_orientations = [Gf.Quath() for _ in range(self.count)]
# specify that all initial prims are related to same geometry
self._instancer_manager.GetProtoIndicesAttr().Set(self._proto_indices)
# set initial positions of the targets
self._instancer_manager.GetPositionsAttr().Set(self._gf_positions)
self._instancer_manager.GetOrientationsAttr().Set(self._gf_orientations)
def set_visibility(self, visible: bool):
"""Sets the visibility of the markers.
The method does this through the USD API.
Args:
visible: flag to set the visibility.
"""
imageable = UsdGeom.Imageable(self._instancer_manager)
if visible:
imageable.MakeVisible()
else:
imageable.MakeInvisible()
def set_world_poses(
self,
positions: np.ndarray | torch.Tensor | None = None,
orientations: np.ndarray | torch.Tensor | None = None,
indices: Sequence[int] | None = None,
):
"""Update marker poses in the simulation world frame.
Args:
positions:
Positions in the world frame. Shape is (M, 3). Defaults to None, which means left unchanged.
orientations:
Quaternion orientations (w, x, y, z) in the world frame of the prims. Shape is (M, 4).
Defaults to None, which means left unchanged.
indices: Indices to specify which alter poses.
Shape is (M,), where M <= total number of markers. Defaults to None (i.e: all markers).
"""
# resolve inputs
if positions is not None:
positions = positions.tolist()
if orientations is not None:
orientations = orientations.tolist()
if indices is None:
indices = range(self.count)
# change marker locations
for i, marker_index in enumerate(indices):
if positions is not None:
self._gf_positions[marker_index][:] = positions[i]
if orientations is not None:
self._gf_orientations[marker_index].SetReal(orientations[i][0])
self._gf_orientations[marker_index].SetImaginary(orientations[i][1:])
# apply to instance manager
self._instancer_manager.GetPositionsAttr().Set(self._gf_positions)
self._instancer_manager.GetOrientationsAttr().Set(self._gf_orientations)
def set_status(self, status: list[int] | np.ndarray | torch.Tensor, indices: Sequence[int] | None = None):
"""Updates the marker activated by the instance manager.
Args:
status: Decides which prototype marker to visualize. Shape is (M)
indices: Indices to specify which alter poses. Shape is (M,), where M <= total number of markers.
Defaults to None (i.e: all markers).
"""
# default values
if indices is None:
indices = range(self.count)
# resolve input
if status is not list:
proto_indices = status.tolist()
else:
proto_indices = status
# change marker locations
for i, marker_index in enumerate(indices):
self._proto_indices[marker_index] = int(proto_indices[i])
# apply to instance manager
self._instancer_manager.GetProtoIndicesAttr().Set(self._proto_indices)
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Utilities to create and visualize 2D height-maps."""
from __future__ import annotations
import matplotlib.pyplot as plt
import numpy as np
from matplotlib.axes import Axes
from matplotlib.image import AxesImage
def create_points_from_grid(size: tuple[float, float], resolution: float) -> np.ndarray:
"""Creates a list of points from 2D mesh-grid.
The terrain scan is approximated with a grid map of the input resolution.
By default, we consider the origin as the center of the local map and the scan size ``(X, Y)`` is the
map size. Given these settings, the elevation map spans from: ``(- X / 2, - Y / 2)`` to
``(+ X / 2, + Y / 2)``.
Example:
For a grid of size (0.2, 0.2) with resolution of 0.1, the created points will first x-axis fixed, while the
y-axis changes, i.e.:
.. code-block:: none
[
[-0.1, -0.1], [-0.1, 0.0], [-0.1, 0.1],
[0.0, -0.1], [0.0, 0.], [0.0, 0.1],
[0.1, -0.1], [0.1, 0.0], [0.1, 0.1],
]
Args:
size: The 2D scan region along x and y directions (in meters).
resolution: The resolution of the scanner (in meters/cell).
Returns:
A set of points of shape (N, 2) or (N, 3), where first x is fixed while y changes.
"""
# Compute the scan grid
# Note: np.arange does not include end-point when dealing with floats. That is why we add resolution.
x = np.arange(-size[0] / 2, size[0] / 2 + resolution, resolution)
y = np.arange(-size[1] / 2, size[1] / 2 + resolution, resolution)
grid = np.meshgrid(x, y, sparse=False, indexing="ij")
# Concatenate the scan grid into points array (N, 2): first x is fixed while y changes
return np.vstack(list(map(np.ravel, grid))).T
def plot_height_grid(
hit_distance: np.ndarray, size: tuple[float, float], resolution: float, ax: Axes = None
) -> AxesImage:
"""Plots the sensor height-map distances using matplotlib.
If the axes is not provided, a new figure is created.
Note:
This method currently only supports if the grid is evenly spaced, i.e. the scan points are created using
:meth:`create_points_from_grid` method.
Args:
hit_distance: The ray hit distance measured from the sensor.
size: The 2D scan region along x and y directions (in meters).
resolution: The resolution of the scanner (in meters/cell).
ax: The current matplotlib axes to plot in.. Defaults to None.
Returns:
Image axes of the created plot.
"""
# Check that request of keys has same length as available axes.
if ax is None:
# Create axes if not provided
# Setup a figure
_, ax = plt.subplots()
# turn axes off
ax.clear()
# resolve shape of the heightmap
x = np.arange(-size[0] / 2, size[0] / 2 + resolution, resolution)
y = np.arange(-size[1] / 2, size[1] / 2 + resolution, resolution)
shape = (len(x), len(y))
# convert the map shape
heightmap = hit_distance.reshape(shape)
# plot the scanned distance
caxes = ax.imshow(heightmap, cmap="turbo", interpolation="none", vmin=0)
# set the label
ax.set_xlabel("y (m)")
ax.set_ylabel("x (m)")
# set the ticks
ax.set_xticks(np.arange(shape[1]), minor=False)
ax.set_yticks(np.arange(shape[0]), minor=False)
ax.set_xticklabels([round(value, 2) for value in y])
ax.set_yticklabels([round(value, 2) for value in x])
# add grid
ax.grid(color="w", linestyle="--", linewidth=1)
# return the color axes
return caxes
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Base class for sensors.
This class defines an interface for sensors similar to how the :class:`omni.isaac.orbit.robot.robot_base.RobotBase` class works.
Each sensor class should inherit from this class and implement the abstract methods.
"""
from __future__ import annotations
from abc import abstractmethod
from typing import Any
from warnings import warn
import carb
class SensorBase:
"""The base class for implementing a sensor.
Note:
These sensors are not vectorized yet.
"""
def __init__(self, sensor_tick: float = 0.0):
"""Initialize the sensor class.
The sensor tick is the time between two sensor buffers. If the sensor tick is zero, then the sensor
buffers are filled at every simulation step.
Args:
sensor_tick: Simulation seconds between sensor buffers. Defaults to 0.0.
"""
# print warning to notify user that the sensor is not vectorized
carb.log_warn("This implementation of the sensor is not vectorized yet. Please use the vectorized version.")
# Copy arguments to class
self._sensor_tick: float = sensor_tick
# Current timestamp of animation (in seconds)
self._timestamp: float = 0.0
# Timestamp from last update
self._timestamp_last_update: float = 0.0
# Frame number when the measurement is taken
self._frame: int = 0
def __init_subclass__(cls, **kwargs):
"""This throws a deprecation warning on subclassing."""
warn(f"{cls.__name__} will be deprecated from v1.0.", DeprecationWarning, stacklevel=1)
super().__init_subclass__(**kwargs)
"""
Properties
"""
@property
def frame(self) -> int:
"""Frame number when the measurement took place."""
return self._frame
@property
def timestamp(self) -> float:
"""Simulation time of the measurement (in seconds)."""
return self._timestamp
@property
def sensor_tick(self) -> float:
"""Simulation seconds between sensor buffers (ticks)."""
return self._sensor_tick
@property
def data(self) -> Any:
"""The data from the simulated sensor."""
return None # noqa: R501
"""
Helpers
"""
def set_visibility(self, visible: bool):
"""Set visibility of the instance in the scene.
Note:
Sensors are mostly XForms which do not have any mesh associated to them. Thus,
overriding this method is optional.
Args:
visible: Whether to make instance visible or invisible.
"""
pass
"""
Operations
"""
@abstractmethod
def spawn(self, parent_prim_path: str):
"""Spawns the sensor into the stage.
Args:
parent_prim_path: The path of the parent prim to attach sensor to.
"""
raise NotImplementedError
@abstractmethod
def initialize(self):
"""Initializes the sensor handles and internal buffers."""
raise NotImplementedError
def reset(self):
"""Resets the sensor internals."""
# Set current time
self._timestamp = 0.0
self._timestamp_last_update = 0.0
# Set zero captures
self._frame = 0
def update(self, dt: float, *args, **kwargs):
"""Updates the buffers at sensor frequency.
This function performs time-based checks and fills the data into the data container. It
calls the function :meth:`buffer()` to fill the data. The function :meth:`buffer()` should
not be called directly.
Args:
dt: The simulation time-step.
args: Other positional arguments passed to function :meth:`buffer()`.
kwargs: Other keyword arguments passed to function :meth:`buffer()`.
"""
# Get current time
self._timestamp += dt
# Buffer the sensor data.
if (self._timestamp - self._timestamp_last_update) >= self._sensor_tick:
# Buffer the data
self.buffer(*args, **kwargs)
# Update the frame count
self._frame += 1
# Update capture time
self._timestamp_last_update = self._timestamp
@abstractmethod
def buffer(self, *args, **kwargs):
"""Fills the buffers of the sensor data.
This function does not perform any time-based checks and directly fills the data into the data container.
Warning:
Although this method is public, `update(dt)` should be the preferred way of filling buffers.
"""
raise NotImplementedError
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import contextlib
import math
from collections.abc import 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: Sequence[float] | None = (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: The prim path to spawn the ground plane at.
z_position: The z-location of the plane. Defaults to 0.
static_friction: The static friction coefficient. Defaults to 1.0.
dynamic_friction: The dynamic friction coefficient. Defaults to 1.0.
restitution: The coefficient of restitution. Defaults to 0.0.
color: The color of the ground plane.
Defaults to (0.065, 0.0725, 0.080).
Keyword Args:
usd_path: 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: Whether to enable patch friction. Defaults to False.
combine_mode: Determines the way physics materials will be combined during collisions.
Available options are `average`, `min`, `multiply`, `multiply`, and `max`. Defaults to `average`.
light_intensity: The power intensity of the light source. Defaults to 1e7.
light_radius: 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,
)
# Add light source
# 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.
ambient_light = kwargs.get("ambient_light", True)
if ambient_light:
attributes = {"intensity": 600.0}
attributes = {f"inputs:{k}": v for k, v in attributes.items()}
# create light prim
prim_utils.create_prim(f"{prim_path}/AmbientLight", "DistantLight", attributes=attributes)
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: The source prim path.
target_ns: 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: float | None = None,
damping: float | None = None,
max_velocity: float | None = None,
max_force: float | None = None,
) -> None:
"""Set the DOF properties of a drive on an articulation.
Args:
prim_path: The prim path to the articulation root.
dof_name: The name of the DOF/joint.
stiffness: The stiffness of the drive.
damping: The damping of the drive.
max_velocity: The max velocity of the drive.
max_force: 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: bool | None = None,
solver_position_iteration_count: int | None = None,
solver_velocity_iteration_count: int | None = None,
sleep_threshold: float | None = None,
stabilization_threshold: float | None = None,
enable_self_collisions: bool | None = None,
) -> None:
"""Set PhysX parameters for an articulation prim.
Args:
prim_path: The prim path to the articulation root.
articulation_enabled: Whether the articulation should be enabled/disabled.
solver_position_iteration_count: Solver position iteration counts for the body.
solver_velocity_iteration_count: Solver velocity iteration counts for the body.
sleep_threshold: Mass-normalized kinetic energy threshold below which an
actor may go to sleep.
stabilization_threshold: The mass-normalized kinetic energy threshold below
which an articulation may participate in stabilization.
enable_self_collisions: 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: bool | None = None,
solver_position_iteration_count: int | None = None,
solver_velocity_iteration_count: int | None = None,
linear_damping: float | None = None,
angular_damping: float | None = None,
max_linear_velocity: float | None = None,
max_angular_velocity: float | None = None,
sleep_threshold: float | None = None,
stabilization_threshold: float | None = None,
max_depenetration_velocity: float | None = None,
max_contact_impulse: float | None = None,
enable_gyroscopic_forces: bool | None = None,
disable_gravity: bool | None = None,
retain_accelerations: bool | None = None,
):
"""Set PhysX parameters for a rigid body prim.
Args:
prim_path: The prim path to the rigid body.
rigid_body_enabled: Whether to enable or disable rigid body API.
solver_position_iteration_count: Solver position iteration counts for the body.
solver_velocity_iteration_count: Solver velocity iteration counts for the body.
linear_damping: Linear damping coefficient.
angular_damping: Angular damping coefficient.
max_linear_velocity: Max allowable linear velocity for rigid body (in m/s).
max_angular_velocity: Max allowable angular velocity for rigid body (in rad/s).
sleep_threshold: Mass-normalized kinetic energy threshold below which an actor
may go to sleep.
stabilization_threshold: Mass-normalized kinetic energy threshold below which
an actor may participate in stabilization.
max_depenetration_velocity: The maximum depenetration velocity permitted to
be introduced by the solver (in m/s).
max_contact_impulse: The limit on the impulse that may be applied at a contact.
enable_gyroscopic_forces: Enables computation of gyroscopic forces on the
rigid body.
disable_gravity: Disable gravity for the actor.
retain_accelerations: 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: bool | None = None,
contact_offset: float | None = None,
rest_offset: float | None = None,
torsional_patch_radius: float | None = None,
min_torsional_patch_radius: float | None = None,
):
"""Set PhysX properties of collider prim.
Args:
prim_path: The prim path of parent.
collision_enabled: Whether to enable/disable collider.
contact_offset: Contact offset of a collision shape (in m).
rest_offset: Rest offset of a collision shape (in m).
torsional_patch_radius: Defines the radius of the contact patch
used to apply torsional friction (in m).
min_torsional_patch_radius: 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: The prim path of parent.
material_path: 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: The prim path under which to search and apply articulation properties.
Keyword Args:
articulation_enabled: Whether the articulation should be enabled/disabled.
solver_position_iteration_count: Solver position iteration counts for the body.
solver_velocity_iteration_count: Solver velocity iteration counts for the body.
sleep_threshold: Mass-normalized kinetic energy threshold below which an
actor may go to sleep.
stabilization_threshold: The mass-normalized kinetic energy threshold below
which an articulation may participate in stabilization.
enable_self_collisions: 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: The prim path under which to search and apply rigid-body properties.
Keyword Args:
rigid_body_enabled: Whether to enable or disable rigid body API.
solver_position_iteration_count: Solver position iteration counts for the body.
solver_velocity_iteration_count: Solver velocity iteration counts for the body.
linear_damping: Linear damping coefficient.
angular_damping: Angular damping coefficient.
max_linear_velocity: Max allowable linear velocity for rigid body (in m/s).
max_angular_velocity: Max allowable angular velocity for rigid body (in rad/s).
sleep_threshold: Mass-normalized kinetic energy threshold below which an actor
may go to sleep.
stabilization_threshold: Mass-normalized kinetic energy threshold below which
an actor may participate in stabilization.
max_depenetration_velocity: The maximum depenetration velocity permitted to
be introduced by the solver (in m/s).
max_contact_impulse: The limit on the impulse that may be applied at a contact.
enable_gyroscopic_forces: Enables computation of gyroscopic forces on the
rigid body.
disable_gravity: Disable gravity for the actor.
retain_accelerations: 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: The prim path under which to search and apply collider properties.
Keyword Args:
collision_enabled: Whether to enable/disable collider.
contact_offset: Contact offset of a collision shape (in m).
rest_offset: Rest offset of a collision shape (in m).
torsional_patch_radius: Defines the radius of the contact patch
used to apply torsional friction (in m).
min_torsional_patch_radius: 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: The prim path under which to search and apply physics material.
material_path: The path to the physics material to apply.
weaker_than_descendants: 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()
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
"""Launch Isaac Sim Simulator first."""
import logging
from omni.isaac.kit import SimulationApp
# launch the simulator
config = {"headless": True}
simulation_app = SimulationApp(config)
# disable matplotlib debug messages
mpl_logger = logging.getLogger("matplotlib")
mpl_logger.setLevel(logging.WARNING)
"""Rest everything follows."""
import numpy as np
import os
import random
import scipy.spatial.transform as tf
import unittest
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.simulation_context import SimulationContext
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.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
class TestCameraSensor(unittest.TestCase):
"""Test fixture for checking camera interface."""
@classmethod
def tearDownClass(cls):
"""Closes simulator after running all test fixtures."""
simulation_app.close()
def setUp(self) -> None:
"""Create a blank new stage for each test."""
# Simulation time-step
self.dt = 0.01
# Load kit helper
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="numpy")
# Set camera view
set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# Fix random seed -- to generate same scene every time
set_seed(0)
# Spawn things into stage
self._populate_scene()
# Wait for spawning
stage_utils.update_stage()
def tearDown(self) -> None:
"""Stops simulator after each test."""
# close all the opened viewport from before.
rep.vp_manager.destroy_hydra_textures()
# stop simulation
self.sim.stop()
self.sim.clear()
def test_camera_resolution(self):
"""Checks that a camera provides image at the resolution specified."""
# Create camera instance
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera = Camera(cfg=camera_cfg, device="cpu")
camera.spawn("/World/CameraSensor")
# Play simulator
self.sim.reset()
# Initialize sensor
camera.initialize()
# perform rendering
self.sim.step()
# update camera
camera.update(self.dt)
# expected camera image shape
height_expected, width_expected = camera.image_shape
# check that the camera image shape is correct
for im_data in camera.data.output.values():
if not isinstance(im_data, np.ndarray):
continue
height, width = im_data.shape[:2]
self.assertEqual(height, height_expected)
self.assertEqual(width, width_expected)
def test_default_camera(self):
"""Checks that the pre-existing stage camera is configured correctly."""
# Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__))
output_dir = os.path.join(test_dir, "output", "camera", "kit_persp")
if not os.path.exists(output_dir):
os.makedirs(output_dir, exist_ok=True)
# Create replicator writer
rep_writer = rep.BasicWriter(output_dir=output_dir, frame_padding=3)
# Create camera instance
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=180,
width=320,
data_types=["rgb", "distance_to_image_plane", "normals", "distance_to_camera"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera = Camera(cfg=camera_cfg, device="cpu")
# Note: the camera is spawned by default in the stage
# camera.spawn("/World/CameraSensor")
# Play simulator
self.sim.reset()
# Initialize sensor
camera.initialize("/OmniverseKit_Persp")
# Set camera pose
set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# Simulate physics
for i in range(10):
# perform rendering
self.sim.step()
# update camera
camera.update(self.dt)
# Save images
rep_writer.write(camera.data.output)
# Check image data
# expect same frame number
self.assertEqual(i + 1, camera.frame)
# expected camera image shape
height_expected, width_expected = camera.image_shape
# check that the camera image shape is correct
for im_data in camera.data.output.values():
if not isinstance(im_data, np.ndarray):
continue
height, width = im_data.shape[:2]
self.assertEqual(height, height_expected)
self.assertEqual(width, width_expected)
def test_single_cam(self):
"""Checks that the single camera gets created properly."""
# Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__))
output_dir = os.path.join(test_dir, "output", "camera", "single")
if not os.path.exists(output_dir):
os.makedirs(output_dir, exist_ok=True)
# Create replicator writer
rep_writer = rep.BasicWriter(output_dir=output_dir, frame_padding=3)
# Create camera instance
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=180,
width=320,
data_types=[
"rgb",
"distance_to_image_plane",
"normals",
"distance_to_camera",
# "instance_segmentation",
# "semantic_segmentation",
"bounding_box_2d_tight",
"bounding_box_2d_loose",
"bounding_box_2d_tight",
"bounding_box_3d",
],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera = Camera(cfg=camera_cfg, device="cpu")
# Note: the camera is spawned by default in the stage
camera.spawn("/World/CameraSensor")
# Play simulator
self.sim.reset()
# Initialize sensor
camera.initialize()
# Set camera position directly
# Note: Not a recommended way but was feeling lazy to do it properly.
camera.set_world_pose_from_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0])
# Simulate physics
for i in range(4):
# perform rendering
self.sim.step()
# update camera
camera.update(self.dt)
# Save images
rep_writer.write(camera.data.output)
# Check image data
# expected camera image shape
height_expected, width_expected = camera.image_shape
# check that the camera image shape is correct
for im_data in camera.data.output.values():
if not isinstance(im_data, np.ndarray):
continue
height, width = im_data.shape[:2]
self.assertEqual(height, height_expected)
self.assertEqual(width, width_expected)
def test_multiple_cam(self):
"""Checks that the multiple cameras created properly."""
# Create camera instance
# -- default viewport
camera_def_cfg = PinholeCameraCfg(
sensor_tick=0,
height=180,
width=320,
data_types=["rgb"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera_def = Camera(cfg=camera_def_cfg, device="cpu")
# -- camera 1
camera1_cfg = PinholeCameraCfg(
sensor_tick=0,
height=180,
width=320,
data_types=["rgb", "distance_to_image_plane", "normals"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera_1 = Camera(cfg=camera1_cfg, device="cpu")
# -- camera 2
camera2_cfg = PinholeCameraCfg(
sensor_tick=0,
height=256,
width=256,
data_types=["rgb", "distance_to_image_plane", "normals", "distance_to_camera"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera_2 = Camera(cfg=camera2_cfg, device="cpu")
# Note: the camera is spawned by default in the stage
camera_1.spawn("/World/CameraSensor1")
camera_2.spawn("/World/CameraSensor2")
# Play simulator
self.sim.reset()
# Initialize sensor
camera_def.initialize("/OmniverseKit_Persp")
camera_1.initialize()
camera_2.initialize()
# Simulate physics
for _ in range(10):
# perform rendering
self.sim.step()
# update camera
camera_def.update(self.dt)
camera_1.update(self.dt)
camera_2.update(self.dt)
# Check image data
for cam in [camera_def, camera_1, camera_2]:
# expected camera image shape
height_expected, width_expected = cam.image_shape
# check that the camera image shape is correct
for im_data in cam.data.output.values():
if not isinstance(im_data, np.ndarray):
continue
height, width = im_data.shape[:2]
self.assertEqual(height, height_expected)
self.assertEqual(width, width_expected)
def test_intrinsic_matrix(self):
"""Checks that the camera's set and retrieve methods work for intrinsic matrix."""
# Create camera instance
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=240,
width=320,
data_types=["rgb", "distance_to_image_plane"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera = Camera(cfg=camera_cfg, device="cpu")
# Note: the camera is spawned by default in the stage
camera.spawn("/World/CameraSensor")
# 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)
# Set matrix into simulator
camera.set_intrinsic_matrix(rs_intrinsic_matrix)
# Play simulator
self.sim.reset()
# Initialize sensor
camera.initialize()
# Simulate physics
for _ in range(10):
# perform rendering
self.sim.step()
# update camera
camera.update(self.dt)
# Check that matrix is correct
K = camera.data.intrinsic_matrix
# TODO: This is not correctly setting all values in the matrix since the
# vertical aperture and aperture offsets are not being set correctly
# 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)
# Display results
print(f">>> Desired intrinsic matrix: \n{rs_intrinsic_matrix}")
print(f">>> Current intrinsic matrix: \n{camera.data.intrinsic_matrix}")
def test_set_pose_ros(self):
"""Checks that the camera's set and retrieve methods work for pose in ROS convention."""
# Create camera instance
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=240,
width=320,
data_types=["rgb", "distance_to_image_plane"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera = Camera(cfg=camera_cfg, device="cpu")
# Note: the camera is spawned by default in the stage
camera.spawn("/World/CameraSensor")
# Play simulator
self.sim.reset()
# Initialize sensor
camera.initialize()
# Simulate physics
for _ in range(10):
# set camera pose randomly
camera_position = np.random.random(3) * 5.0
camera_orientation = convert_quat(tf.Rotation.random().as_quat(), "wxyz")
camera.set_world_pose_ros(pos=camera_position, quat=camera_orientation)
# perform rendering
self.sim.step()
# update camera
camera.update(self.dt)
# Check that pose is correct
# -- position
np.testing.assert_almost_equal(camera.data.position, camera_position, 4)
# -- orientation
if np.sign(camera.data.orientation[0]) != np.sign(camera_orientation[0]):
camera_orientation *= -1
np.testing.assert_almost_equal(camera.data.orientation, camera_orientation, 4)
def test_set_pose_from_view(self):
"""Checks that the camera's set method works for look-at pose."""
# Create camera instance
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=240,
width=320,
data_types=["rgb", "distance_to_image_plane"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera = Camera(cfg=camera_cfg, device="cpu")
# Note: the camera is spawned by default in the stage
camera.spawn("/World/CameraSensor")
# Play simulator
self.sim.reset()
# Initialize sensor
camera.initialize()
# Test look-at pose
# -- inputs
eye = np.array([2.5, 2.5, 2.5])
targets = [np.array([0.0, 0.0, 0.0]), np.array([2.5, 2.5, 0.0])]
# -- expected outputs
camera_position = eye.copy()
camera_orientations = [
np.array([-0.17591989, 0.33985114, 0.82047325, -0.42470819]),
np.array([0.0, 1.0, 0.0, 0.0]),
]
# check that the camera pose is correct
for target, camera_orientation in zip(targets, camera_orientations):
# set camera pose
camera.set_world_pose_from_view(eye=eye, target=target)
# perform rendering
self.sim.step()
# update camera
camera.update(self.dt)
# Check that pose is correct
# -- position
np.testing.assert_almost_equal(camera.data.position, camera_position, 4)
# # -- orientation
if np.sign(camera.data.orientation[0]) != np.sign(camera_orientation[0]):
camera_orientation *= -1
np.testing.assert_almost_equal(camera.data.orientation, camera_orientation, 4)
def test_throughput(self):
"""Checks that the single camera gets created properly with a rig."""
# Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__))
output_dir = os.path.join(test_dir, "output", "camera", "throughput")
if not os.path.exists(output_dir):
os.makedirs(output_dir, exist_ok=True)
# Create replicator writer
rep_writer = rep.BasicWriter(output_dir=output_dir, frame_padding=3)
# Create camera instance
camera_cfg = PinholeCameraCfg(
sensor_tick=0,
height=480,
width=640,
data_types=["rgb", "distance_to_image_plane"],
usd_params=PinholeCameraCfg.UsdCameraCfg(clipping_range=(0.1, 1.0e5)),
)
camera = Camera(cfg=camera_cfg, device="cpu")
# Note: the camera is spawned by default in the stage
camera.spawn("/World/CameraSensor")
# Play simulator
self.sim.reset()
# Initialize sensor
camera.initialize()
# Set camera pose
camera.set_world_pose_from_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0])
# Simulate physics
for _ in range(5):
# perform rendering
self.sim.step()
# update camera
with Timer(f"Time taken for updating camera with shape {camera.image_shape}"):
camera.update(self.dt)
# Save images
with Timer(f"Time taken for writing data with shape {camera.image_shape} "):
rep_writer.write(camera.data.output)
print("----------------------------------------")
# Check image data
# expected camera image shape
height_expected, width_expected = camera.image_shape
# check that the camera image shape is correct
for im_data in camera.data.output.values():
if not isinstance(im_data, np.ndarray):
continue
height, width = im_data.shape[:2]
self.assertEqual(height, height_expected)
self.assertEqual(width, width_expected)
"""
Helper functions.
"""
@staticmethod
def _populate_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))
# Lights-2
prim_utils.create_prim("/World/Light/WhiteSphere", "SphereLight", translation=(-4.5, 3.5, 10.0))
# 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])
if __name__ == "__main__":
unittest.main(verbosity=2)
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
"""Launch Isaac Sim Simulator first."""
import logging
from omni.isaac.kit import SimulationApp
# launch the simulator
config = {"headless": True}
simulation_app = SimulationApp(config)
# disable matplotlib debug messages
mpl_logger = logging.getLogger("matplotlib")
mpl_logger.setLevel(logging.WARNING)
"""Rest everything follows."""
import matplotlib.pyplot as plt
import numpy as np
import os
import random
import scipy.spatial.transform as tf
import unittest
import omni.isaac.core.utils.prims as prim_utils
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.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
from omni.isaac.orbit.utils.timer import Timer
class TestHeightScannerSensor(unittest.TestCase):
"""Test fixture for checking height scanner interface."""
@classmethod
def tearDownClass(cls):
"""Closes simulator after running all test fixtures."""
simulation_app.close()
def setUp(self) -> None:
"""Create a blank new stage for each test."""
# Simulation time-step
self.dt = 0.1
# Load kit helper
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="numpy")
# Set camera view
set_camera_view(eye=[5.0, 5.0, 5.0], target=[0.0, 0.0, 0.0])
# Spawn things into stage
self._populate_scene()
# Add height scanner
# -- create query points from a gri
self.grid_size = (1.0, 0.6)
self.grid_resolution = 0.1
scan_points = create_points_from_grid(self.grid_size, self.grid_resolution)
# -- create sensor instance
scanner_config = HeightScannerCfg(
sensor_tick=0.0,
offset=(0.0, 0.0, 0.0),
points=scan_points,
max_distance=0.45,
)
self.height_scanner = HeightScanner(scanner_config)
# -- spawn sensor
self.height_scanner.spawn("/World/heightScanner")
self.height_scanner.set_visibility(True)
def tearDown(self) -> None:
"""Stops simulator after each test."""
self.sim.stop()
self.sim.clear()
def test_height_scanner_visibility(self):
"""Checks that height map visibility method works."""
# Play simulator
self.sim.reset()
# Setup the stage
self.height_scanner.initialize()
# flag for visualizing sensor
toggle = True
# Simulate physics
for i in range(100):
# set visibility
if i % 100 == 0:
toggle = not toggle
print(f"Setting visibility: {toggle}")
self.height_scanner.set_visibility(toggle)
# perform rendering
self.sim.step()
# compute yaw -> quaternion
yaw = 10 * i
quat = tf.Rotation.from_euler("z", yaw, degrees=True).as_quat()
quat = convert_quat(quat, "wxyz")
# update sensor
self.height_scanner.update(self.dt, [0.0, 0.0, 0.5], quat)
def test_static_height_scanner(self):
"""Checks that static height map scanner is set correctly and provides right measurements."""
# Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__))
plot_dir = os.path.join(test_dir, "output", "height_scan", "static")
if not os.path.exists(plot_dir):
os.makedirs(plot_dir, exist_ok=True)
# Play simulator
self.sim.reset()
# Setup the stage
self.height_scanner.initialize()
# Simulate physics
for i in range(5):
# perform rendering
self.sim.step()
# update camera
self.height_scanner.update(self.dt, [0.0, 0.0, 0.5], [1.0, 0.0, 0.0, 0.0])
# print state
print(self.height_scanner)
# create figure
fig = plt.figure()
ax = plt.gca()
# plot the scanned distance
caxes = plot_height_grid(self.height_scanner.data.hit_distance, self.grid_size, self.grid_resolution, ax=ax)
fig.colorbar(caxes, ax=ax)
# add grid
ax.grid(color="w", linestyle="--", linewidth=1)
# disreset figure
plt.savefig(os.path.join(plot_dir, f"{i:03d}.png"), bbox_inches="tight", pad_inches=0.1)
plt.close()
def test_dynamic_height_scanner(self):
"""Checks that height map scanner works when base frame is rotating."""
# Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__))
plot_dir = os.path.join(test_dir, "output", "height_scan", "dynamic")
if not os.path.exists(plot_dir):
os.makedirs(plot_dir, exist_ok=True)
# Play simulator
self.sim.reset()
# Setup the stage
self.height_scanner.initialize()
# Simulate physics
for i in range(5):
# perform rendering
self.sim.step()
# compute yaw -> quaternion
yaw = 10 * i
quat = tf.Rotation.from_euler("z", yaw, degrees=True).as_quat()
quat = convert_quat(quat, "wxyz")
# update sensor
self.height_scanner.update(self.dt, [0.0, 0.0, 0.5], quat)
# create figure
fig = plt.figure()
ax = plt.gca()
# plot the scanned distance
caxes = plot_height_grid(self.height_scanner.data.hit_distance, self.grid_size, self.grid_resolution, ax=ax)
fig.colorbar(caxes, ax=ax)
# add grid
ax.grid(color="w", linestyle="--", linewidth=1)
# disreset figure
plt.savefig(os.path.join(plot_dir, f"{i:03d}.png"), bbox_inches="tight", pad_inches=0.1)
plt.close()
def test_height_scanner_filtering(self):
"""Checks that static height map scanner filters out the ground prim.
The first time, all the cube prims are ignored. After that, they are ignored one-by-one cyclically.
"""
# Create directory to dump results
test_dir = os.path.dirname(os.path.abspath(__file__))
plot_dir = os.path.join(test_dir, "output", "height_scan", "filter")
if not os.path.exists(plot_dir):
os.makedirs(plot_dir, exist_ok=True)
# Configure filter prims
self.height_scanner.set_filter_prims([f"/World/Cube/cube{i:02d}" for i in range(4)])
# Play simulator
self.sim.reset()
# Setup the stage
self.height_scanner.initialize()
# Simulate physics
for i in range(6):
# set different filter prims
if i > 0:
cube_id = i - 1
self.height_scanner.set_filter_prims([f"/World/Cube/cube{cube_id:02}"])
if i > 4:
self.height_scanner.set_filter_prims(None)
# perform rendering
self.sim.step()
# update sensor
self.height_scanner.update(self.dt, [0.0, 0.0, 0.5], [1.0, 0.0, 0.0, 0.0])
# create figure
fig = plt.figure()
ax = plt.gca()
# plot the scanned distance
caxes = plot_height_grid(self.height_scanner.data.hit_distance, self.grid_size, self.grid_resolution, ax=ax)
fig.colorbar(caxes, ax=ax)
# add grid
ax.grid(color="w", linestyle="--", linewidth=1)
# disreset figure
plt.savefig(os.path.join(plot_dir, f"{i:03d}.png"), bbox_inches="tight", pad_inches=0.1)
plt.close()
def test_scanner_throughput(self):
"""Measures the scanner throughput while using scan points used for ANYmal robot."""
# Add height scanner
# -- create sensor instance
scanner_config = HeightScannerCfg(
sensor_tick=0.0,
offset=(0.0, 0.0, 0.0),
points=self._compute_anymal_height_scanner_points(),
max_distance=1.0,
)
self.anymal_height_scanner = HeightScanner(scanner_config)
# -- spawn sensor
self.anymal_height_scanner.spawn("/World/heightScannerAnymal")
self.anymal_height_scanner.set_visibility(True)
# Play simulator
self.sim.reset()
# Setup the stage
self.anymal_height_scanner.initialize()
# Turn rendering on
self.anymal_height_scanner.set_visibility(True)
# Simulate physics
for i in range(2):
# perform rendering
self.sim.step()
# update sensor
with Timer(f"[No Vis , Step {i:02d}]: Scanning time for {scanner_config.points.shape[0]} points"):
self.anymal_height_scanner.update(self.dt, [0.0, 0.0, 0.5], [1.0, 0.0, 0.0, 0.0])
# Turn rendering off
self.anymal_height_scanner.set_visibility(False)
# Simulate physics
for i in range(2):
# perform rendering
self.sim.step()
# update sensor
with Timer(f"[With Vis, Step {i:02d}] Scanning time for {scanner_config.points.shape[0]} points"):
self.anymal_height_scanner.update(self.dt, [0.0, 0.0, 0.5], [1.0, 0.0, 0.0, 0.0])
"""
Helper functions.
"""
@staticmethod
def _populate_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))
# Lights-2
prim_utils.create_prim("/World/Light/WhiteSphere", "SphereLight", translation=(-4.5, 3.5, 10.0))
# Cubes
num_cubes = 4
for i in range(num_cubes):
# resolve position to put them on vertex of a regular polygon
theta = 2 * np.pi / num_cubes
c, s = np.cos(theta * i), np.sin(theta * i)
rotm = np.array([[c, -s, 0], [s, c, 0], [0, 0, 1]])
position = np.matmul(rotm, np.asarray([0.25, 0.25, 0.1 + 0.05 * i]))
color = np.array([random.random(), random.random(), random.random()])
# create prim
_ = DynamicCuboid(
prim_path=f"/World/Cube/cube{i:02d}", position=position, size=position[2] * 2, color=color
)
@staticmethod
def _compute_anymal_height_scanner_points() -> np.ndarray:
"""Computes the query height-scan points relative to base frame of robot.
Returns:
A numpy array of shape (N, 3) comprising of quey scan points.
"""
# offset from the base frame - over each leg
offsets = [[0.45, 0.3, 0.0], [-0.46, 0.3, 0.0], [0.45, -0.3, 0.0], [-0.46, -0.3, 0.0]]
offsets = np.asarray(offsets)
# local grid over each offset point
measurement_points = [
[0.1, 0.0, 0.0],
[0.0, 0.1, 0.0],
[-0.1, 0.0, 0.0],
[0.0, -0.1, 0.0],
[0.1, 0.1, 0.0],
[-0.1, 0.1, 0.0],
[0.1, -0.1, 0.0],
[-0.1, -0.1, 0.0],
[0.2, 0.0, 0.0],
[0.0, 0.2, 0.0],
[-0.2, 0.0, 0.0],
[0.0, -0.2, 0.0],
[0.2, 0.2, 0.0],
[-0.2, 0.2, 0.0],
[0.2, -0.2, 0.0],
[-0.2, -0.2, 0.0],
[0.3, 0.0, 0.0],
[0.3, 0.1, 0.0],
[0.3, 0.2, 0.0],
[0.3, -0.1, 0.0],
[0.3, -0.2, 0.0],
[-0.3, 0.0, 0.0],
[-0.3, 0.1, 0.0],
[-0.3, 0.2, 0.0],
[-0.3, -0.1, 0.0],
[-0.3, -0.2, 0.0],
[0.0, 0.0, 0.0],
]
measurement_points = np.asarray(measurement_points)
# create a joined list over offsets and local measurement points
# we use broadcasted addition to make this operation quick
scan_points = (offsets[:, None, :] + measurement_points).reshape(-1, 3)
return scan_points
if __name__ == "__main__":
unittest.main()
# Copyright (c) 2022-2024, The ORBIT Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
"""Launch Isaac Sim Simulator first."""
from omni.isaac.kit import SimulationApp
# launch the simulator
config = {"headless": False}
simulation_app = SimulationApp(config)
"""Rest everything follows."""
import unittest
import omni.isaac.core.utils.prims as prim_utils
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.compat.utils.kit as kit_utils
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
class TestKitUtilities(unittest.TestCase):
"""Test fixture for checking Kit utilities in Orbit."""
@classmethod
def tearDownClass(cls):
"""Closes simulator after running all test fixtures."""
simulation_app.close()
def setUp(self) -> None:
"""Create a blank new stage for each test."""
# Simulation time-step
self.dt = 0.1
# Load kit helper
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, backend="numpy")
# Set camera view
set_camera_view(eye=[1.0, 1.0, 1.0], target=[0.0, 0.0, 0.0])
# Spawn things into stage
self._populate_scene()
# Wait for spawning
stage_utils.update_stage()
def tearDown(self) -> None:
"""Stops simulator after each test."""
# stop simulation
self.sim.stop()
self.sim.clear()
def test_rigid_body_properties(self):
"""Disable setting of rigid body properties."""
# create marker
prim_utils.create_prim(
"/World/marker", usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd"
)
# set marker properties
kit_utils.set_nested_rigid_body_properties("/World/marker", rigid_body_enabled=False)
kit_utils.set_nested_collision_properties("/World/marker", collision_enabled=False)
# play simulation
self.sim.reset()
for _ in range(5):
self.sim.step()
"""
Helper functions.
"""
@staticmethod
def _populate_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))
# Lights-2
prim_utils.create_prim("/World/Light/WhiteSphere", "SphereLight", translation=(-4.5, 3.5, 10.0))
if __name__ == "__main__":
unittest.main()
......@@ -9,9 +9,6 @@ TESTS_TO_SKIP = [
"test_argparser_launch.py", # app.close issue
"test_env_var_launch.py", # app.close issue
"test_kwarg_launch.py", # app.close issue
"compat/test_kit_utils.py", # Compat to be deprecated
"compat/sensors/test_height_scanner.py", # Compat to be deprecated
"compat/sensors/test_camera.py", # Timing out
"test_differential_ik.py", # Failing
# orbit_tasks
"test_data_collector.py", # Failing
......
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