Unverified Commit f3c7fe59 authored by Pascal Roth's avatar Pascal Roth Committed by GitHub

Adds lidar pattern for raycaster sensor (#616)

# Description

Add a lidar pattern for the `RayCaster` sensor. The pattern is
determined by number of channels, horizontal and vertical field of view
and corresponding horizontal resolution. An example config for a
Velodyne VLP 16 is provided.

## Type of change

- New feature (non-breaking change which adds functionality)

## Screenshots

![Screenshot from 2024-07-02
10-13-45](https://github.com/isaac-sim/IsaacLab/assets/57946385/31c87608-9d4d-4a11-9ad5-1ced954aa750)

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.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 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 da34688b
......@@ -49,3 +49,13 @@ RS-Bpearl Pattern
:members:
:inherited-members:
:exclude-members: __init__, func
LiDAR Pattern
-------------
.. autofunction:: omni.isaac.lab.sensors.patterns.lidar_pattern
.. autoclass:: LidarPatternCfg
:members:
:inherited-members:
:exclude-members: __init__, func
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.19.0"
version = "0.19.1"
# Description
title = "Isaac Lab framework for Robot Learning"
......
Changelog
---------
0.19.1 (2024-07-05)
~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added a lidar pattern function :func:`~omni.isaac.lab.sensors.ray_caster.patterns.patterns.lidar_pattern` with
corresponding config :class:`~omni.isaac.lab.sensors.ray_caster.patterns_cfg.LidarPatternCfg`.
0.19.0 (2024-07-04)
~~~~~~~~~~~~~~~~~~~
......
......@@ -5,5 +5,5 @@
"""Sub-module for ray-casting patterns used by the ray-caster."""
from .patterns import bpearl_pattern, grid_pattern, pinhole_camera_pattern
from .patterns_cfg import BpearlPatternCfg, GridPatternCfg, PatternBaseCfg, PinholeCameraPatternCfg
from .patterns import bpearl_pattern, grid_pattern, lidar_pattern, pinhole_camera_pattern
from .patterns_cfg import BpearlPatternCfg, GridPatternCfg, LidarPatternCfg, PatternBaseCfg, PinholeCameraPatternCfg
......@@ -5,6 +5,7 @@
from __future__ import annotations
import math
import torch
from typing import TYPE_CHECKING
......@@ -128,3 +129,49 @@ def bpearl_pattern(cfg: patterns_cfg.BpearlPatternCfg, device: str) -> tuple[tor
ray_directions = -torch.stack([x, y, z], dim=1)
ray_starts = torch.zeros_like(ray_directions)
return ray_starts, ray_directions
def lidar_pattern(cfg: patterns_cfg.LidarPatternCfg, device: str) -> tuple[torch.Tensor, torch.Tensor]:
"""Lidar sensor pattern for ray casting.
Args:
cfg: The configuration instance for the pattern.
device: The device to create the pattern on.
Returns:
The starting positions and directions of the rays.
"""
# Vertical angles
vertical_angles = torch.linspace(cfg.vertical_fov_range[0], cfg.vertical_fov_range[1], cfg.channels)
# If the horizontal field of view is 360 degrees, exclude the last point to avoid overlap
if abs(abs(cfg.horizontal_fov_range[0] - cfg.horizontal_fov_range[1]) - 360.0) < 1e-6:
up_to = -1
else:
up_to = None
# Horizontal angles
num_horizontal_angles = math.ceil((cfg.horizontal_fov_range[1] - cfg.horizontal_fov_range[0]) / cfg.horizontal_res)
horizontal_angles = torch.linspace(cfg.horizontal_fov_range[0], cfg.horizontal_fov_range[1], num_horizontal_angles)[
:up_to
]
# Convert degrees to radians
vertical_angles_rad = torch.deg2rad(vertical_angles)
horizontal_angles_rad = torch.deg2rad(horizontal_angles)
# Meshgrid to create a 2D array of angles
v_angles, h_angles = torch.meshgrid(vertical_angles_rad, horizontal_angles_rad, indexing="ij")
# Spherical to Cartesian conversion (assuming Z is up)
x = torch.cos(v_angles) * torch.cos(h_angles)
y = torch.cos(v_angles) * torch.sin(h_angles)
z = torch.sin(v_angles)
# Ray directions
ray_directions = torch.stack([x, y, z], dim=-1).reshape(-1, 3).to(device)
# Ray starts: Assuming all rays originate from (0,0,0)
ray_starts = torch.zeros_like(ray_directions).to(device)
return ray_starts, ray_directions
......@@ -122,3 +122,22 @@ class BpearlPatternCfg(PatternBaseCfg):
We manually set the vertical ray angles to match the Bpearl sensor. The ray-angles
are not evenly spaced.
"""
@configclass
class LidarPatternCfg(PatternBaseCfg):
"""Configuration for the LiDAR pattern for ray-casting."""
func: Callable = patterns.lidar_pattern
channels: int = MISSING
"""Number of Channels (Beams). Determines the vertical resolution of the LiDAR sensor."""
vertical_fov_range: tuple[float, float] = MISSING
"""Vertical field of view range in degrees."""
horizontal_fov_range: tuple[float, float] = MISSING
"""Horizontal field of view range in degrees."""
horizontal_res: float = MISSING
"""Horizontal resolution (in degrees)."""
......@@ -22,8 +22,11 @@ Reference:
import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.actuators import ActuatorNetLSTMCfg, DCMotorCfg
from omni.isaac.lab.assets.articulation import ArticulationCfg
from omni.isaac.lab.sensors import RayCasterCfg
from omni.isaac.lab.utils.assets import ISAACLAB_NUCLEUS_DIR
from .velodyne import VELODYNE_VLP_16_RAYCASTER_CFG
##
# Configuration - Actuators.
##
......@@ -160,3 +163,13 @@ Note:
Since we don't have a publicly available actuator network for ANYmal-D, we use the same network as ANYmal-C.
This may impact the sim-to-real transfer performance.
"""
##
# Configuration - Sensors.
##
ANYMAL_LIDAR_CFG = VELODYNE_VLP_16_RAYCASTER_CFG.replace(
offset=RayCasterCfg.OffsetCfg(pos=(-0.310, 0.000, 0.159), rot=(0.0, 0.0, 0.0, 1.0))
)
"""Configuration for the Velodyne VLP-16 sensor mounted on the ANYmal robot's base."""
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Configuration for Velodyne LiDAR sensors."""
from omni.isaac.lab.sensors import RayCasterCfg, patterns
##
# Configuration
##
VELODYNE_VLP_16_RAYCASTER_CFG = RayCasterCfg(
attach_yaw_only=False,
pattern_cfg=patterns.LidarPatternCfg(
channels=16, vertical_fov_range=(-15.0, 15.0), horizontal_fov_range=(-180.0, 180.0), horizontal_res=0.2
),
debug_vis=True,
max_distance=100,
)
"""Configuration for Velodyne Puck LiDAR (VLP-16) as a :class:`RayCasterCfg`.
Reference: https://velodynelidar.com/wp-content/uploads/2019/12/63-9229_Rev-K_Puck-_Datasheet_Web.pdf
"""
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