Unverified Commit 6442cef5 authored by Pascal Roth's avatar Pascal Roth Committed by GitHub

Updates sensors to follow structure similar to assets (#123)

# Description

This MR adapts all the sensor classes to follow a structure similar to
the `assets` classes. This removes the need to worry about the spawning
and initialization of sensors manually by the users. It removes the
`debug_vis` function since that is now handled by a render callback
automatically (based on the passed configuration for the `debug_vis`
flag).

Additionally, the camera poses can now be set and obtained different
conventions:

* `opengl`: the camera is looking down the -Z axis with the +Y axis
pointing up
* `ros`: the camera is looking down the +Z axis with the +Y axis
pointing down
* `world`: the camera is looking along the +X axis with the -Z axis
pointing down

## Type of change

- New feature (non-breaking change which adds functionality)
- Breaking change (fix or feature that would cause existing
functionality to not work as expected)
- This change requires a documentation update

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./orbit.sh --format`
- [ ] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file

---------
Co-authored-by: 's avatarMayank Mittal <mittalma@leggedrobotics.com>
parent 5802697c
BSD License
For PyTorch3D software
Copyright (c) Meta Platforms, Inc. and affiliates. All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
* Neither the name Meta nor the names of its contributors may be used to
endorse or promote products derived from this software without specific
prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.9.0"
version = "0.9.1"
# Description
title = "ORBIT framework for Robot Learning"
......
Changelog
---------
0.9.1 (2023-08-18)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Introduced three different rotation conventions in the :class:`omni.isaac.orbit.sensors.Camera` class. These
conventions are:
* ``opengl``: the camera is looking down the -Z axis with the +Y axis pointing up
* ``ros``: the camera is looking down the +Z axis with the +Y axis pointing down
* ``world``: the camera is looking along the +X axis with the -Z axis pointing down
These can be used to declare the camera offset in :class:`omni.isaac.orbit.sensors.CameraCfg.OffsetCfg` class
and in :meth:`omni.isaac.orbit.sensors.Camera.set_world_pose` method. Additionally, all conventions are
saved to :class:`omni.isaac.orbit.sensors.CameraData` class for easy access.
Changed
^^^^^^^
* Adapted all the sensor classes to follow a structure similar to the :class:`omni.issac.orbit.assets.AssetBase`.
Hence, the spawning and initialization of sensors manually by the users is avoided.
* Removed the :meth:`debug_vis` function since that this functionality is handled by a render callback automatically
(based on the passed configuration for the :class:`omni.isaac.orbit.sensors.SensorBaseCfg.debug_vis` flag).
0.9.0 (2023-08-18)
~~~~~~~~~~~~~~~~~~
......
......@@ -8,7 +8,8 @@ Camera wrapper around USD camera prim to provide an interface that follows the r
"""
from .camera import Camera
from .camera_cfg import FisheyeCameraCfg, PinholeCameraCfg
from .camera_cfg import CameraCfg
from .camera_data import CameraData
from .utils import * # noqa: F401, F403
__all__ = ["Camera", "CameraData", "PinholeCameraCfg", "FisheyeCameraCfg"]
__all__ = ["Camera", "CameraData", "CameraCfg"]
......@@ -3,66 +3,68 @@
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the camera sensor."""
from __future__ import annotations
from dataclasses import MISSING
from typing import List, Tuple
from typing_extensions import Literal
from omni.isaac.orbit.sim import FisheyeCameraCfg, PinholeCameraCfg
from omni.isaac.orbit.utils import configclass
from ..sensor_base_cfg import SensorBaseCfg
__all__ = ["PinholeCameraCfg", "FisheyeCameraCfg"]
from .camera import Camera
@configclass
class PinholeCameraCfg(SensorBaseCfg):
"""Configuration for a pinhole camera sensor."""
class CameraCfg(SensorBaseCfg):
"""Configuration for a camera sensor."""
@configclass
class UsdCameraCfg:
"""USD related configuration of the sensor.
class OffsetCfg:
"""The offset pose of the sensor's frame from the sensor's parent frame."""
The parameter is kept default from USD if it is set to :obj:`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).
pos: tuple[float, float, float] = (0.0, 0.0, 0.0)
"""Translation w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0)."""
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
"""
rot: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0)
"""Quaternion rotation ``(w, x, y, z)`` w.r.t. the parent frame. Defaults to (1.0, 0.0, 0.0, 0.0)."""
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).
convention: Literal["opengl", "ros", "world"] = "ros"
"""The convention in which the frame offset is applied. Defaults to "ros".
The distance at which perfect sharpness is achieved.
"""
f_stop: float = None
"""Lens aperture. Defaults to 0.0, which turns off focusing.
- ``"opengl"`` - forward axis: ``-Z`` - up axis: ``+Y`` - Offset is applied in the OpenGL (Usd.Camera) convention.
- ``"ros"`` - forward axis: ``+Z`` - up axis: ``-Y`` - Offset is applied in the ROS convention.
- ``"world"`` - forward axis: ``+X`` - up axis: ``+Z`` - Offset is applied in the World Frame convention.
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."""
cls_name = "Camera"
cls_name = Camera
offset: OffsetCfg = OffsetCfg()
"""The offset pose of the sensor's frame from the sensor's parent frame. Defaults to identity.
Note:
The parent frame is the frame the sensor attaches to. For example, the parent frame of a
camera at path ``/World/envs/env_0/Robot/Camera`` is ``/World/envs/env_0/Robot``.
"""
spawn: PinholeCameraCfg | FisheyeCameraCfg | None = MISSING
"""Spawn configuration for the asset.
If :obj:`None`, then the prim is not spawned by the asset. Instead, it is assumed that the
asset is already present in the scene.
"""
data_types: List[str] = ["rgb"]
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"]
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
......@@ -71,6 +73,7 @@ class PinholeCameraCfg(SensorBaseCfg):
More information available at:
https://docs.omniverse.nvidia.com/app_code/prod_extensions/ext_replicator/semantic_schema_editor.html
"""
colorize: bool = False
"""whether to output colorized semantic information or non-colorized one. Defaults to False.
......@@ -80,42 +83,3 @@ class PinholeCameraCfg(SensorBaseCfg):
If False, the semantic images will be a 2D array of integers, where each pixel is an integer representing
the semantic ID. Accordingly, the information output will contain mapping from semantic ID to semantic labels.
"""
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."""
import numpy as np
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import torch
from dataclasses import dataclass
from tensordict import TensorDict
from typing import Any, Dict, List, Tuple, Union
from omni.isaac.orbit.utils.array import TensorData
from typing import Any
@dataclass
class CameraData:
"""Data container for the camera sensor."""
position: TensorData = None
##
# Frame state.
##
pos_w: torch.Tensor = None
"""Position of the sensor origin in world frame, following ROS convention.
Shape is (N, 3) where ``N`` is the number of sensors.
"""
orientation: TensorData = None
quat_w_ros: torch.Tensor = None
"""Quaternion orientation `(w, x, y, z)` of the sensor origin in world frame, following ROS convention.
.. note::
ROS convention follows the camera aligned with forward axis +Z and up axis -Y.
Shape: (N, 4) where ``N`` is the number of sensors.
"""
intrinsic_matrices: TensorData = None
quat_w_world: torch.Tensor = None
"""Quaternion orientation `(w, x, y, z)` of the sensor origin in world frame, following the world coordinate frame
.. note::
World frame convention follows the camera aligned with forward axis +X and up axis +Z.
Shape: (N, 4) where ``N`` is the number of sensors.
"""
quat_w_opengl: torch.Tensor = None
"""Quaternion orientation `(w, x, y, z)` of the sensor origin in world frame, following Opengl / Usd.Camera convention
.. note::
OpenGL convention follows the camera aligned with forward axis -Z and up axis +Y.
Shape: (N, 4) where ``N`` is the number of sensors.
"""
##
# Camera data
##
image_shape: tuple[int, int] = None
"""A tuple containing (height, width) of the camera sensor."""
intrinsic_matrices: torch.Tensor = None
"""The intrinsic matrices for the camera.
Shape is (N, 3, 3) where ``N`` is the number of sensors.
"""
image_shape: Tuple[int, int] = None
"""A tuple containing (height, width) of the camera sensor."""
output: Union[Dict[str, np.ndarray], TensorDict] = None
output: TensorDict = None
"""The retrieved sensor data with sensor types as key.
The format of the data is available in the `Replicator Documentation`_. For semantic-based data,
......@@ -35,7 +73,8 @@ class CameraData:
.. _Replicator Documentation: https://docs.omniverse.nvidia.com/prod_extensions/prod_extensions/ext_replicator/annotators_details.html#annotator-output
"""
info: List[Dict[str, Any]] = None
info: list[dict[str, Any]] = None
"""The retrieved sensor info with sensor types as key.
This contains extra information provided by the sensor such as semantic segmentation label mapping, prim paths.
......
......@@ -4,17 +4,25 @@
# SPDX-License-Identifier: BSD-3-Clause
"""Helper functions to project between pointcloud and depth images."""
from __future__ import annotations
import math
import numpy as np
import torch
from typing import Optional, Sequence, Tuple, Union
from typing import Sequence
from typing_extensions import Literal
import warp as wp
import omni.isaac.orbit.utils.math as math_utils
from omni.isaac.orbit.utils.array import TensorData, convert_to_torch
__all__ = ["transform_points", "create_pointcloud_from_depth", "create_pointcloud_from_rgbd"]
__all__ = [
"transform_points",
"create_pointcloud_from_depth",
"create_pointcloud_from_rgbd",
"convert_orientation_convention",
]
"""
......@@ -24,10 +32,10 @@ Depth <-> Pointcloud conversions.
def transform_points(
points: TensorData,
position: Optional[Sequence[float]] = None,
orientation: Optional[Sequence[float]] = None,
device: Union[torch.device, str, None] = None,
) -> Union[np.ndarray, torch.Tensor]:
position: Sequence[float] | None = None,
orientation: Sequence[float] | None = None,
device: torch.device | str | None = None,
) -> np.ndarray | torch.Tensor:
r"""Transform input points in a given frame to a target frame.
This function transform points from a source frame to a target frame. The transformation is defined by the
......@@ -78,13 +86,13 @@ def transform_points(
def create_pointcloud_from_depth(
intrinsic_matrix: Union[np.ndarray, torch.Tensor, wp.array],
depth: Union[np.ndarray, torch.Tensor, wp.array],
intrinsic_matrix: np.ndarray | torch.Tensor | wp.array,
depth: np.ndarray | torch.Tensor | wp.array,
keep_invalid: bool = False,
position: Optional[Sequence[float]] = None,
orientation: Optional[Sequence[float]] = None,
device: Optional[Union[torch.device, str]] = None,
) -> Union[np.ndarray, torch.Tensor]:
position: Sequence[float] | None = None,
orientation: Sequence[float] | None = None,
device: torch.device | str | None = None,
) -> np.ndarray | torch.Tensor:
r"""Creates pointcloud from input depth image and camera intrinsic matrix.
This function creates a pointcloud from a depth image and camera intrinsic matrix. The pointcloud is
......@@ -162,15 +170,15 @@ def create_pointcloud_from_depth(
def create_pointcloud_from_rgbd(
intrinsic_matrix: Union[torch.Tensor, np.ndarray, wp.array],
depth: Union[torch.Tensor, np.ndarray, wp.array],
rgb: Union[torch.Tensor, wp.array, np.ndarray, Tuple[float, float, float]] = None,
intrinsic_matrix: torch.Tensor | np.ndarray | wp.array,
depth: torch.Tensor | np.ndarray | wp.array,
rgb: torch.Tensor | wp.array | np.ndarray | tuple[float, float, float] = None,
normalize_rgb: bool = False,
position: Optional[Sequence[float]] = None,
orientation: Optional[Sequence[float]] = None,
device: Optional[Union[torch.device, str]] = None,
position: Sequence[float] | None = None,
orientation: Sequence[float] | None = None,
device: torch.device | str | None = None,
num_channels: int = 3,
) -> Union[Tuple[torch.Tensor, torch.Tensor], Tuple[np.ndarray, np.ndarray]]:
) -> tuple[torch.Tensor, torch.Tensor] | tuple[np.ndarray, np.ndarray]:
"""Creates pointcloud from input depth image and camera transformation matrix.
This function provides the same functionality as :meth:`create_pointcloud_from_depth` but also allows
......@@ -243,7 +251,7 @@ def create_pointcloud_from_rgbd(
# convert the matrix to (W, H, 3) from (H, W, 3) since depth processing
# is done in the order (u, v) where u: (0, W-1) and v: (0 - H-1)
points_rgb = rgb.permute(1, 0, 2).reshape(-1, 3)
elif isinstance(rgb, Tuple):
elif isinstance(rgb, (tuple, list)):
# same color for all points
points_rgb = torch.Tensor((rgb,) * num_points, device=device, dtype=torch.uint8)
else:
......@@ -269,3 +277,90 @@ def create_pointcloud_from_rgbd(
return points_xyz.cpu().numpy(), points_rgb.cpu().numpy()
else:
return points_xyz, points_rgb
def convert_orientation_convention(
orientation: torch.Tensor,
origin: Literal["opengl", "ros", "world"] = "opengl",
target: Literal["opengl", "ros", "world"] = "ros",
) -> torch.Tensor:
r"""Converts a quaternion representing a rotation from one convention to another.
In USD, the camera follows the ``"opengl"`` convention. Thus, it 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}
On the other hand, the typical world coordinate system is with +X pointing forward, +Y pointing left,
and +Z pointing up. The camera can also be set in this convention by rotating the camera by :math:`90^{\circ}`
around the X axis and :math:`-90^{\circ}` around the Y axis.
.. math::
T_{WORLD} = \begin{bmatrix} 0 & 0 & -1 & 0 \\ -1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix} T_{USD}
Thus, based on their application, cameras follow different conventions for their orientation. This function
converts a quaternion from one convention to another.
Possible conventions are:
- :obj:"opengl" - forward axis: -Z - up axis +Y - Offset is applied in the OpenGL (Usd.Camera) convention
- :obj:"ros" - forward axis: +Z - up axis -Y - Offset is applied in the ROS convention
- :obj:"world" - forward axis: +X - up axis +Z - Offset is applied in the World Frame convention
Args:
orientation torch.Tensor: Quaternion of form `(w, x, y, z)` with shape (..., 4) in source convention
origin (Literal["opengl", "ros", "world"], optional): Convention to convert to. Defaults to "ros".
target (Literal["opengl", "ros", "world"], optional): Convention to convert from. Defaults to "opengl".
Returns:
torch.Tensor: Quaternion of form `(w, x, y, z)` with shape (..., 4) in target convention
"""
if target == origin:
return orientation
# -- unify input type
if origin == "ros":
# convert from ros to opengl convention
rotm = math_utils.matrix_from_quat(orientation)
rotm[:, :, 2] = -rotm[:, :, 2]
rotm[:, :, 1] = -rotm[:, :, 1]
# convert to opengl convention
quat_gl = math_utils.quat_from_matrix(rotm)
elif origin == "world":
# convert from world (x forward and z up) to opengl convention
rotm = math_utils.matrix_from_quat(orientation)
rotm = torch.matmul(
rotm,
math_utils.matrix_from_euler(
torch.tensor([math.pi / 2, -math.pi / 2, 0], device=orientation.device), "XYZ"
),
)
# convert to isaac-sim convention
quat_gl = math_utils.quat_from_matrix(rotm)
else:
quat_gl = orientation
# -- convert to target convention
if target == "ros":
# convert from opengl to ros convention
rotm = math_utils.matrix_from_quat(quat_gl)
rotm[:, :, 2] = -rotm[:, :, 2]
rotm[:, :, 1] = -rotm[:, :, 1]
return math_utils.quat_from_matrix(rotm)
elif target == "world":
# convert from opengl to world (x forward and z up) convention
rotm = math_utils.matrix_from_quat(quat_gl)
rotm = torch.matmul(
rotm,
math_utils.matrix_from_euler(
torch.tensor([math.pi / 2, -math.pi / 2, 0], device=orientation.device), "XYZ"
).T,
)
return math_utils.quat_from_matrix(rotm)
else:
return quat_gl
......@@ -3,21 +3,20 @@
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for the contact sensor."""
from __future__ import annotations
from omni.isaac.orbit.utils import configclass
from ..sensor_base_cfg import SensorBaseCfg
from .contact_sensor import ContactSensor
@configclass
class ContactSensorCfg(SensorBaseCfg):
"""Configuration for the contact sensor."""
cls_name = "ContactSensor"
cls_name = ContactSensor
filter_prim_paths_expr: list[str] = list()
"""The list of primitive paths to filter contacts with.
......@@ -29,7 +28,3 @@ class ContactSensorCfg(SensorBaseCfg):
If an empty list is provided, then only net contact forces are reported.
"""
history_length: int = 0
"""Number of past frames to store in the sensor buffers. Defaults to 0, which means that only
the current data is stored."""
......@@ -8,18 +8,16 @@ Ray-caster based on warp.
"""
from .patterns_cfg import BpearlPatternCfg, GridPatternCfg, PatternBaseCfg, PinholeCameraPatternCfg
from . import patterns
from .ray_caster import RayCaster
from .ray_caster_cfg import RayCasterCfg
from .ray_caster_data import RayCasterData
__all__ = [
# sensor
"RayCaster",
"RayCasterData",
"RayCasterCfg",
# patterns
"PatternBaseCfg",
"GridPatternCfg",
"PinholeCameraPatternCfg",
"BpearlPatternCfg",
"patterns",
]
# Copyright (c) 2022, NVIDIA CORPORATION & AFFILIATES, ETH Zurich, and University of Toronto
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""
Utility functions for different ray-casting patterns that are used by the ray-caster.
"""
from .patterns import bpearl_pattern, grid_pattern, pinhole_camera_pattern
from .patterns_cfg import BpearlPatternCfg, GridPatternCfg, PatternBaseCfg, PinholeCameraPatternCfg
__all__ = [
"PatternBaseCfg",
# grid pattern
"GridPatternCfg",
"grid_pattern",
# pinhole camera pattern
"PinholeCameraPatternCfg",
"pinhole_camera_pattern",
# bpearl pattern
"BpearlPatternCfg",
"bpearl_pattern",
]
......@@ -11,10 +11,10 @@ import torch
from typing import TYPE_CHECKING
if TYPE_CHECKING:
from .patterns_cfg import BpearlPatternCfg, GridPatternCfg, PinholeCameraPatternCfg
from . import patterns_cfg
def grid_pattern(cfg: GridPatternCfg, device: str) -> tuple[torch.Tensor, torch.Tensor]:
def grid_pattern(cfg: patterns_cfg.GridPatternCfg, device: str) -> tuple[torch.Tensor, torch.Tensor]:
"""A regular grid pattern for ray casting.
The grid pattern is made from rays that are parallel to each other. They span a 2D grid in the sensor's
......@@ -41,7 +41,7 @@ def grid_pattern(cfg: GridPatternCfg, device: str) -> tuple[torch.Tensor, torch.
return ray_starts, ray_directions
def pinhole_camera_pattern(cfg: PinholeCameraPatternCfg, device: str) -> tuple[torch.Tensor, torch.Tensor]:
def pinhole_camera_pattern(cfg: patterns_cfg.PinholeCameraPatternCfg, device: str) -> tuple[torch.Tensor, torch.Tensor]:
"""The depth-image pattern for ray casting.
Args:
......@@ -64,7 +64,7 @@ def pinhole_camera_pattern(cfg: PinholeCameraPatternCfg, device: str) -> tuple[t
return ray_starts, ray_directions
def bpearl_pattern(cfg: BpearlPatternCfg, device: str) -> tuple[torch.Tensor, torch.Tensor]:
def bpearl_pattern(cfg: patterns_cfg.BpearlPatternCfg, device: str) -> tuple[torch.Tensor, torch.Tensor]:
"""The RS-Bpearl pattern for ray casting.
The `Robosense RS-Bpearl`_ is a short-range LiDAR that has a 360 degrees x 90 degrees super wide
......
......@@ -13,14 +13,24 @@ from dataclasses import MISSING
from omni.isaac.orbit.utils import configclass
from ..sensor_base_cfg import SensorBaseCfg
from .patterns_cfg import PatternBaseCfg
from .patterns.patterns_cfg import PatternBaseCfg
from .ray_caster import RayCaster
@configclass
class RayCasterCfg(SensorBaseCfg):
"""Configuration for the ray-cast sensor."""
cls_name = "RayCaster"
@configclass
class OffsetCfg:
"""The offset pose of the sensor's frame from the sensor's parent frame."""
pos: tuple[float, float, float] = (0.0, 0.0, 0.0)
"""Translation w.r.t. the parent frame. Defaults to (0.0, 0.0, 0.0)."""
rot: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0)
"""Quaternion rotation ``(w, x, y, z)`` w.r.t. the parent frame. Defaults to (1.0, 0.0, 0.0, 0.0)."""
cls_name = RayCaster
mesh_prim_paths: list[str] = MISSING
"""The list of mesh primitive paths to ray cast against.
......@@ -30,11 +40,8 @@ class RayCasterCfg(SensorBaseCfg):
static meshes and dynamic meshes.
"""
pos_offset: tuple[float, float, float] = (0.0, 0.0, 0.0)
"""The position offset from the frame the sensor is attached to. Defaults to (0.0, 0.0, 0.0)."""
quat_offset: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0)
"""The quaternion offset (w, x, y, z) from the frame the sensor is attached to. Defaults to (1.0, 0.0, 0.0, 0.0)."""
offset: OffsetCfg = OffsetCfg()
"""The offset pose of the sensor's frame from the sensor's parent frame. Defaults to identity."""
attach_yaw_only: bool = MISSING
"""Whether the rays' starting positions and directions only track the yaw orientation.
......
......@@ -4,7 +4,7 @@
# SPDX-License-Identifier: BSD-3-Clause
from dataclasses import MISSING
from typing import ClassVar, Optional
from typing import ClassVar
from omni.isaac.orbit.utils import configclass
......@@ -13,17 +13,25 @@ from omni.isaac.orbit.utils import configclass
class SensorBaseCfg:
"""Configuration parameters for a sensor."""
cls_name: ClassVar[str] = MISSING
"""Name of the associated sensor class."""
cls_name: ClassVar[type] = MISSING
"""The associated sensor class."""
prim_path_expr: Optional[str] = None
"""Relative path to the prim on which the sensor should be attached. Defaults to None."""
prim_path: str = MISSING
"""Prim path (or expression) to the asset.
.. note::
The expression can contain the environment namespace regex ``{ENV_REGEX_NS}`` which
will be replaced with the environment namespace.
Example: ``{ENV_REGEX_NS}/Robot/sensor`` will be replaced with ``/World/envs/env_.*/Robot/sensor`.
"""
update_period: float = 0.0
"""Update period of the sensor buffers (in seconds). Defaults to 0.0 (update every step)."""
history_length: int = 0
"""Number of past frames to store in the sensor buffers. Defaults to 0 (no history)."""
"""Number of past frames to store in the sensor buffers. Defaults to 0, which means that only
the current data is stored (no history)."""
debug_vis: bool = False
"""Whether to visualize the sensor. Defaults to False."""
......@@ -35,8 +35,10 @@ __all__ = [
"unscale_transform",
# Rotation
"matrix_from_quat",
"matrix_from_euler",
"quat_inv",
"quat_from_euler_xyz",
"quat_from_matrix",
"quat_apply_yaw",
"quat_box_minus",
"yaw_quat",
......@@ -160,14 +162,14 @@ def matrix_from_quat(quaternions: torch.Tensor) -> torch.Tensor:
return o.reshape(quaternions.shape[:-1] + (3, 3))
def convert_quat(quat: Union[torch.tensor, Sequence[float]], to: Optional[str] = "xyzw") -> torch.tensor:
def convert_quat(quat: Union[torch.Tensor, Sequence[float]], to: Optional[str] = "xyzw") -> torch.Tensor:
"""Converts quaternion from one convention to another.
The convention to convert TO is specified as an optional argument. If to == 'xyzw',
then the input is in 'wxyz' format, and vice-versa.
Args:
quat (Union[torch.tensor, Sequence[float]]): Input quaternion of shape (..., 4).
quat (Union[torch.Tensor, Sequence[float]]): Input quaternion of shape (..., 4).
to (Optional[str], optional): Convention to convert quaternion to.. Defaults to "xyzw".
Raises:
......@@ -175,7 +177,7 @@ def convert_quat(quat: Union[torch.tensor, Sequence[float]], to: Optional[str] =
ValueError: Invalid shape of input `quat`, i.e. not (..., 4,).
Returns:
torch.tensor: The converted quaternion in specified convention.
torch.Tensor: The converted quaternion in specified convention.
"""
# convert to torch (sanity check)
if not isinstance(quat, torch.Tensor):
......@@ -241,6 +243,148 @@ def quat_from_euler_xyz(roll: torch.Tensor, pitch: torch.Tensor, yaw: torch.Tens
return torch.stack([qw, qx, qy, qz], dim=-1)
@torch.jit.script
def _sqrt_positive_part(x: torch.Tensor) -> torch.Tensor:
"""
Returns torch.sqrt(torch.max(0, x))
but with a zero subgradient where x is 0.
Reference:
Based on PyTorch3D (https://github.com/facebookresearch/pytorch3d/blob/main/pytorch3d/transforms/rotation_conversions.py#L91-L99)
"""
ret = torch.zeros_like(x)
positive_mask = x > 0
ret[positive_mask] = torch.sqrt(x[positive_mask])
return ret
@torch.jit.script
def quat_from_matrix(matrix: torch.Tensor) -> torch.Tensor:
"""
Convert rotations given as rotation matrices to quaternions.
Args:
matrix: Rotation matrices as tensor of shape (..., 3, 3).
Returns:
quaternions with real part first, as tensor of shape (..., 4).
Reference:
Based on PyTorch3D (https://github.com/facebookresearch/pytorch3d/blob/main/pytorch3d/transforms/rotation_conversions.py#L102-L161)
"""
if matrix.size(-1) != 3 or matrix.size(-2) != 3:
raise ValueError(f"Invalid rotation matrix shape {matrix.shape}.")
batch_dim = matrix.shape[:-2]
m00, m01, m02, m10, m11, m12, m20, m21, m22 = torch.unbind(matrix.reshape(batch_dim + (9,)), dim=-1)
q_abs = _sqrt_positive_part(
torch.stack(
[
1.0 + m00 + m11 + m22,
1.0 + m00 - m11 - m22,
1.0 - m00 + m11 - m22,
1.0 - m00 - m11 + m22,
],
dim=-1,
)
)
# we produce the desired quaternion multiplied by each of r, i, j, k
quat_by_rijk = torch.stack(
[
# pyre-fixme[58]: `**` is not supported for operand types `Tensor` and
# `int`.
torch.stack([q_abs[..., 0] ** 2, m21 - m12, m02 - m20, m10 - m01], dim=-1),
# pyre-fixme[58]: `**` is not supported for operand types `Tensor` and
# `int`.
torch.stack([m21 - m12, q_abs[..., 1] ** 2, m10 + m01, m02 + m20], dim=-1),
# pyre-fixme[58]: `**` is not supported for operand types `Tensor` and
# `int`.
torch.stack([m02 - m20, m10 + m01, q_abs[..., 2] ** 2, m12 + m21], dim=-1),
# pyre-fixme[58]: `**` is not supported for operand types `Tensor` and
# `int`.
torch.stack([m10 - m01, m20 + m02, m21 + m12, q_abs[..., 3] ** 2], dim=-1),
],
dim=-2,
)
# We floor here at 0.1 but the exact level is not important; if q_abs is small,
# the candidate won't be picked.
flr = torch.tensor(0.1).to(dtype=q_abs.dtype, device=q_abs.device)
quat_candidates = quat_by_rijk / (2.0 * q_abs[..., None].max(flr))
# if not for numerical problems, quat_candidates[i] should be same (up to a sign),
# forall i; we pick the best-conditioned one (with the largest denominator)
return quat_candidates[torch.nn.functional.one_hot(q_abs.argmax(dim=-1), num_classes=4) > 0.5, :].reshape(
batch_dim + (4,)
)
def _axis_angle_rotation(axis: str, angle: torch.Tensor) -> torch.Tensor:
"""
Return the rotation matrices for one of the rotations about an axis
of which Euler angles describe, for each value of the angle given.
Args:
axis: Axis label "X" or "Y or "Z".
angle: any shape tensor of Euler angles in radians
Returns:
Rotation matrices as tensor of shape (..., 3, 3).
Reference:
Based on PyTorch3D (https://github.com/facebookresearch/pytorch3d/blob/main/pytorch3d/transforms/rotation_conversions.py#L164-L191)
"""
cos = torch.cos(angle)
sin = torch.sin(angle)
one = torch.ones_like(angle)
zero = torch.zeros_like(angle)
if axis == "X":
R_flat = (one, zero, zero, zero, cos, -sin, zero, sin, cos)
elif axis == "Y":
R_flat = (cos, zero, sin, zero, one, zero, -sin, zero, cos)
elif axis == "Z":
R_flat = (cos, -sin, zero, sin, cos, zero, zero, zero, one)
else:
raise ValueError("letter must be either X, Y or Z.")
return torch.stack(R_flat, -1).reshape(angle.shape + (3, 3))
def matrix_from_euler(euler_angles: torch.Tensor, convention: str) -> torch.Tensor:
"""
Convert rotations given as Euler angles in radians to rotation matrices.
Args:
euler_angles: Euler angles in radians as tensor of shape (..., 3).
convention: Convention string of three uppercase letters from
{"X", "Y", and "Z"}.
Returns:
Rotation matrices as tensor of shape (..., 3, 3).
Reference:
Based on PyTorch3D (https://github.com/facebookresearch/pytorch3d/blob/main/pytorch3d/transforms/rotation_conversions.py#L194-L220)
"""
if euler_angles.dim() == 0 or euler_angles.shape[-1] != 3:
raise ValueError("Invalid input euler angles.")
if len(convention) != 3:
raise ValueError("Convention must have 3 letters.")
if convention[1] in (convention[0], convention[2]):
raise ValueError(f"Invalid convention {convention}.")
for letter in convention:
if letter not in ("X", "Y", "Z"):
raise ValueError(f"Invalid letter {letter} in convention string.")
matrices = [_axis_angle_rotation(c, e) for c, e in zip(convention, torch.unbind(euler_angles, -1))]
# return functools.reduce(torch.matmul, matrices)
return torch.matmul(torch.matmul(matrices[0], matrices[1]), matrices[2])
@torch.jit.script
def euler_xyz_from_quat(quat: torch.Tensor) -> Tuple[torch.Tensor, torch.Tensor, torch.Tensor]:
"""
......@@ -607,7 +751,7 @@ def unproject_depth(depth: torch.Tensor, intrinsics: torch.Tensor) -> torch.Tens
deal with many possible shapes of depth images and intrinsics matrices.
Args:
depth (torch.tensor): The depth measurement. Shape: (H, W) or or (H, W, 1) or (N, H, W) or (N, H, W, 1).
depth (torch.Tensor): The depth measurement. Shape: (H, W) or or (H, W, 1) or (N, H, W) or (N, H, W, 1).
intrinsics (torch.Tensor): A tensor providing camera's calibration matrix. Shape: (3, 3) or (N, 3, 3).
Returns:
......
......@@ -19,9 +19,9 @@ import argparse
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Contact Sensor Test Script")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--num_robots", type=int, default=128, help="Number of robots to spawn.")
parser.add_argument("--num_robots", type=int, default=64, help="Number of robots to spawn.")
args_cli = parser.parse_args()
# launch omniverse app
......@@ -42,8 +42,8 @@ from omni.isaac.core.utils.carb import set_carb_setting
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.robots.config.anymal import ANYMAL_C_CFG
from omni.isaac.orbit.robots.legged_robot import LeggedRobot
from omni.isaac.orbit.assets import Articulation
from omni.isaac.orbit.assets.articulation.config.anymal import ANYMAL_C_CFG
from omni.isaac.orbit.sensors.contact_sensor import ContactSensor, ContactSensorCfg
"""
......@@ -97,27 +97,22 @@ def main():
cloner.define_base_env("/World/envs")
# Everything under the namespace "/World/envs/env_0" will be cloned
prim_utils.define_prim("/World/envs/env_0")
# Spawn things into the scene
robot = LeggedRobot(cfg=ANYMAL_C_CFG)
robot.spawn("/World/envs/env_0/Robot")
# Contact sensor
contact_sensor_cfg = ContactSensorCfg(
prim_path_expr="Robot/.*_SHANK", debug_vis=False if args_cli.headless else True
)
contact_sensor = ContactSensor(cfg=contact_sensor_cfg)
# design props
design_scene()
# Clone the scene
num_envs = args_cli.num_robots
cloner.define_base_env("/World/envs")
envs_prim_paths = cloner.generate_paths("/World/envs/env", num_paths=num_envs)
envs_positions = cloner.clone(
source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True
_ = cloner.clone(source_prim_path="/World/envs/env_0", prim_paths=envs_prim_paths, replicate_physics=True)
# Design props
design_scene()
# Spawn things into the scene
robot_cfg = ANYMAL_C_CFG.replace(prim_path="/World/envs/env_.*/Robot")
robot_cfg.spawn.activate_contact_sensors = True
robot = Articulation(cfg=robot_cfg)
# Contact sensor
contact_sensor_cfg = ContactSensorCfg(
prim_path="/World/envs/env_.*/Robot/.*_SHANK", debug_vis=False if args_cli.headless else True
)
# convert environment positions to torch tensor
envs_positions = torch.tensor(envs_positions, dtype=torch.float, device=sim.device)
contact_sensor = ContactSensor(cfg=contact_sensor_cfg)
# filter collisions within each environment instance
physics_scene_path = sim.get_physics_context().prim_path
cloner.filter_collisions(
......@@ -126,18 +121,12 @@ def main():
# Play the simulator
sim.reset()
# Acquire handles
# Initialize handles
robot.initialize("/World/envs/env_.*/Robot")
contact_sensor.initialize("/World/envs/env_.*")
# print info
print(contact_sensor)
# Now we are ready!
print("[INFO]: Setup complete...")
# dummy actions
actions = robot.data.default_dof_pos
# Define simulation stepping
decimation = 4
sim_dt = decimation * sim.get_physics_dt()
......@@ -158,32 +147,30 @@ def main():
sim_time = 0.0
count = 0
# reset dof state
dof_pos = robot.data.default_dof_pos
dof_vel = robot.data.default_dof_vel
robot.set_dof_state(dof_pos, dof_vel)
robot.reset_buffers()
# reset command
actions = robot.data.default_dof_pos
joint_pos, joint_vel = robot.data.default_joint_pos, robot.data.default_joint_vel
robot.write_joint_state_to_sim(joint_pos, joint_vel)
robot.reset()
# perform 4 steps
for _ in range(decimation):
# apply actions
robot.set_dof_position_targets(actions)
robot.set_joint_position_targets(robot.data.default_joint_pos)
# write commands to sim
robot.write_commands_to_sim()
robot.write_data_to_sim()
# perform step
sim.step(render=not args_cli.headless)
# fetch data
robot.refresh_sim_data(refresh_dofs=True)
robot.fetch_data_from_sim()
# update sim-time
sim_time += sim_dt
count += 1
# update the buffers
if sim.is_playing():
robot.update_buffers(sim_dt)
robot.update(sim_dt)
contact_sensor.update(sim_dt, force_recompute=True)
# update marker visualization
if not args_cli.headless:
contact_sensor.debug_vis()
if count % 100 == 0:
print("Sim-time: ", sim_time)
print("Number of contacts: ", torch.count_nonzero(contact_sensor.data.current_air_time == 0.0).item())
print("-" * 80)
if __name__ == "__main__":
......
......@@ -19,14 +19,14 @@ import argparse
from omni.isaac.kit import SimulationApp
# add argparse arguments
parser = argparse.ArgumentParser("Welcome to Orbit: Omniverse Robotics Environments!")
parser = argparse.ArgumentParser(description="Ray Caster Test Script")
parser.add_argument("--headless", action="store_true", default=False, help="Force display off at all times.")
parser.add_argument("--num_envs", type=int, default=128, help="Number of environments to clone.")
parser.add_argument(
"--terrain_type",
type=str,
default="generated",
help="Type of terrain to import. Can be 'generated' or 'usd' or 'plane'.",
default="generator",
help="Type of terrain to import. Can be 'generator' or 'usd' or 'plane'.",
)
args_cli = parser.parse_args()
......@@ -49,8 +49,7 @@ from omni.isaac.core.simulation_context import SimulationContext
from omni.isaac.core.utils.viewports import set_camera_view
import omni.isaac.orbit.terrains as terrain_gen
import omni.isaac.orbit.utils.kit as kit_utils
from omni.isaac.orbit.sensors.ray_caster import GridPatternCfg, RayCaster, RayCasterCfg
from omni.isaac.orbit.sensors.ray_caster import RayCaster, RayCasterCfg, patterns
from omni.isaac.orbit.terrains.config.rough import ROUGH_TERRAINS_CFG
from omni.isaac.orbit.terrains.terrain_importer import TerrainImporter
from omni.isaac.orbit.utils.assets import ISAAC_NUCLEUS_DIR
......@@ -112,27 +111,21 @@ def main():
# Design the scene
design_scene(sim=sim, num_envs=num_envs)
# Handler for terrains importing
if args_cli.terrain_type == "generated":
terrain_importer_cfg = terrain_gen.TerrainImporterCfg(
prim_path="/World/ground",
terrain_type="generator",
terrain_generator=ROUGH_TERRAINS_CFG,
max_init_terrain_level=None,
)
terrain_importer = TerrainImporter(terrain_importer_cfg, num_envs=1, device=sim.device)
elif args_cli.terrain_type == "usd":
prim_utils.create_prim("/World/ground", usd_path=f"{ISAAC_NUCLEUS_DIR}/Environments/Terrains/rough_plane.usd")
elif args_cli.terrain_type == "plane":
kit_utils.create_ground_plane("/World/ground")
else:
raise NotImplementedError(f"Terrain type {args_cli.terrain_type} not supported!")
terrain_importer_cfg = terrain_gen.TerrainImporterCfg(
prim_path="/World/ground",
terrain_type=args_cli.terrain_type,
terrain_generator=ROUGH_TERRAINS_CFG,
usd_path=f"{ISAAC_NUCLEUS_DIR}/Environments/Terrains/rough_plane.usd",
max_init_terrain_level=None,
num_envs=1,
)
terrain_importer = TerrainImporter(terrain_importer_cfg)
# Create a ray-caster sensor
pattern_cfg = GridPatternCfg(resolution=0.1, size=(1.6, 1.0))
ray_caster_cfg = RayCasterCfg(
prim_path_expr="ball",
prim_path="/World/envs/env_.*/ball",
mesh_prim_paths=["/World/ground"],
pattern_cfg=pattern_cfg,
pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=(1.6, 1.0)),
attach_yaw_only=True,
debug_vis=False if args_cli.headless else True,
)
......@@ -146,8 +139,6 @@ def main():
# Initialize the views
# -- balls
ball_view.initialize()
# -- sensors
ray_caster.initialize("/World/envs/env_.*")
# Print the sensor information
print(ray_caster)
......@@ -176,18 +167,14 @@ def main():
)
ball_view.set_velocities(ball_initial_velocities[reset_indices], indices=reset_indices)
# reset the sensor
ray_caster.reset_buffers(reset_indices)
ray_caster.reset(reset_indices)
# reset the counter
step_count = 0
# Step simulation
sim.step()
# Update the ray-caster
with Timer(f"Ray-caster update with {ray_caster.count} x {ray_caster.num_rays} rays"):
with Timer(f"Ray-caster update with {num_envs} x {ray_caster.num_rays} rays"):
ray_caster.update(dt=sim.get_physics_dt(), force_recompute=True)
# Visualize the ray-caster
if not args_cli.headless:
with Timer(f"Ray-caster debug visualization\t\t"):
ray_caster.debug_vis()
# Update counter
step_count += 1
......
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