From 5b73f20290d4d72f9d5bae9a7014830ba9c41686 Mon Sep 17 00:00:00 2001 From: Alexandre Date: Mon, 7 Oct 2024 11:27:01 +0200 Subject: [PATCH 01/15] Fix camera limitation due to jpg encoding (#171) * Switch compressed image to raw image * Remove 'compressed' from camera topic name in camera prefab --- .../Scripts/Data/Texture/ITextureInterface.cs | 4 ++ .../Scripts/Sensors/Camera/CameraSensor.cs | 54 ++++++++++++++----- .../Prefabs/Camera/DepthCamera_ros.prefab | 2 +- .../Prefabs/Camera/RGBCamera_ros.prefab | 2 +- .../Publishers/Image/ImageMsgPublisher.cs | 2 +- .../Serializers/Image/ImageMsgSerializer.cs | 14 ++--- 6 files changed, 57 insertions(+), 21 deletions(-) diff --git a/Assets/UnitySensors/Runtime/Scripts/Data/Texture/ITextureInterface.cs b/Assets/UnitySensors/Runtime/Scripts/Data/Texture/ITextureInterface.cs index cd196100..3c22e8ab 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Data/Texture/ITextureInterface.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Data/Texture/ITextureInterface.cs @@ -5,5 +5,9 @@ namespace UnitySensors.Data.Texture public interface ITextureInterface { public Texture2D texture { get; } + public byte[] data { get; } + public int width { get; } + public int height { get; } + public string encoding { get; } } } diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs index be86f7d4..95881da9 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs @@ -20,11 +20,17 @@ public abstract class CameraSensor : UnitySensor, ITextureInterface private UnityEngine.Camera _m_camera; private RenderTexture _rt = null; private Texture2D _texture; + private byte[] _data; public Vector2Int resolution { get => _resolution; } protected float maxRange { get => _maxRange; } public UnityEngine.Camera m_camera { get => _m_camera; } public Texture2D texture { get => _texture; } + public byte[] data { get => _data; } + public int width { get => _resolution.x; } + public int height { get => _resolution.y; } + public string encoding { get => "rgb8"; } + protected override void Init() { @@ -33,16 +39,18 @@ protected override void Init() _m_camera.nearClipPlane = _minRange; _m_camera.farClipPlane = _maxRange; - _rt = new RenderTexture(_resolution.x, _resolution.y, 32, RenderTextureFormat.ARGBFloat); + _rt = new RenderTexture(_resolution.x, _resolution.y, 16, RenderTextureFormat.ARGB32); _m_camera.targetTexture = _rt; - _texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBAFloat, false); + _texture = new Texture2D(width, height, TextureFormat.RGB24, false); + + _data = new byte[width * height * 3]; } protected override void UpdateSensor() { if (!LoadTexture()) return; - + if (onSensorUpdated != null) onSensorUpdated.Invoke(); } @@ -50,15 +58,31 @@ protected override void UpdateSensor() protected bool LoadTexture() { bool result = false; - AsyncGPUReadback.Request(_rt, 0, request => { - if (request.hasError) - { - } - else - { - var data = request.GetData(); - _texture.LoadRawTextureData(data); + + // Blit to a temporary texture and request readback on it. + AsyncGPUReadback.Request(_rt, 0, TextureFormat.ARGB32, request => { + if (request.hasError) { + Debug.LogWarning("GPU readback error was detected."); + } else { + var dataBuffer = request.GetData(); + + // Flip image + int i=0; + int j=width*(height-1)*4; + for(int y=0; y : RosMsgPublisher, CompressedImageMsg> where T : UnitySensor, ITextureInterface + public class ImageMsgPublisher : RosMsgPublisher, ImageMsg> where T : UnitySensor, ITextureInterface { } } diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Image/ImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Image/ImageMsgSerializer.cs index 7255046b..83198512 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Image/ImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Image/ImageMsgSerializer.cs @@ -7,25 +7,27 @@ namespace UnitySensors.ROS.Serializer.Image { [System.Serializable] - public class ImageMsgSerializer : RosMsgSerializer where T : UnitySensor, ITextureInterface + public class ImageMsgSerializer : RosMsgSerializer where T : UnitySensor, ITextureInterface { [SerializeField] private HeaderSerializer _header; - [SerializeField, Range(1, 100)] - private int quality = 75; public override void Init(T sensor) { base.Init(sensor); _header.Init(sensor); - _msg.format = "jpeg"; + _msg.height = (uint)sensor.height; + _msg.width = (uint)sensor.width; + _msg.encoding = sensor.encoding; + _msg.is_bigendian = 0; + _msg.step = 1 * 3 * _msg.width; } - public override CompressedImageMsg Serialize() + public override ImageMsg Serialize() { _msg.header = _header.Serialize(); - _msg.data = sensor.texture.EncodeToJPG(quality); + _msg.data = sensor.data; return _msg; } } From 739fdb7938489250c619390d61c5e5990e1249a3 Mon Sep 17 00:00:00 2001 From: Ryodo Tanaka Date: Wed, 9 Oct 2024 12:07:13 +0900 Subject: [PATCH 02/15] Update to test unity2020.3.x to 2022.3.x for beta/2.x.x (#182) * Update to test unity2020.3.x to 2022.3.x * Delete unnecessary files * Fix to delete unnecessary file copy --- .github/workflows/activation.yml | 22 -------- .github/workflows/activation2020.yml | 22 -------- .github/workflows/activation2021.yml | 22 -------- .github/workflows/activation2022.yml | 22 -------- .github/workflows/main.yml | 84 +++++++++++++++++----------- 5 files changed, 50 insertions(+), 122 deletions(-) delete mode 100644 .github/workflows/activation.yml delete mode 100644 .github/workflows/activation2020.yml delete mode 100644 .github/workflows/activation2021.yml delete mode 100644 .github/workflows/activation2022.yml diff --git a/.github/workflows/activation.yml b/.github/workflows/activation.yml deleted file mode 100644 index 9825a8b8..00000000 --- a/.github/workflows/activation.yml +++ /dev/null @@ -1,22 +0,0 @@ -name: Acquire activation file -on: - pull_request: - branches: - - master -jobs: - activation: - name: Request manual activation file 🔑 - runs-on: ubuntu-latest - steps: - # Request manual activation file - - name: Request manual activation file - id: getManualLicenseFile - uses: webbertakken/unity-request-manual-activation-file@v1.1 - with: - unityVersion: 2020.1.13f1 - # Upload artifact (Unity_v20XX.X.XXXX.alf) - - name: Expose as artifact - uses: actions/upload-artifact@v1 - with: - name: ${{ steps.getManualLicenseFile.outputs.filePath }} - path: ${{ steps.getManualLicenseFile.outputs.filePath }} diff --git a/.github/workflows/activation2020.yml b/.github/workflows/activation2020.yml deleted file mode 100644 index 2a4409ad..00000000 --- a/.github/workflows/activation2020.yml +++ /dev/null @@ -1,22 +0,0 @@ -name: Acquire activation file for 2020 - -on: - workflow_dispatch: {} - -jobs: - activation: - name: Request manual activation file 🔑 - runs-on: ubuntu-latest - steps: - # Request manual activation file - - name: Request manual activation file - id: getManualLicenseFile - uses: game-ci/unity-request-activation-file@v2 - with: - unityVersion: 2020.3.48f1 - # Upload artifact (Unity_v20XX.X.XXXX.alf) - - name: Expose as artifact - uses: actions/upload-artifact@v2 - with: - name: ${{ steps.getManualLicenseFile.outputs.filePath }} - path: ${{ steps.getManualLicenseFile.outputs.filePath }} diff --git a/.github/workflows/activation2021.yml b/.github/workflows/activation2021.yml deleted file mode 100644 index cfe85c2c..00000000 --- a/.github/workflows/activation2021.yml +++ /dev/null @@ -1,22 +0,0 @@ -name: Acquire activation file for 2021 - -on: - workflow_dispatch: {} - -jobs: - activation: - name: Request manual activation file 🔑 - runs-on: ubuntu-latest - steps: - # Request manual activation file - - name: Request manual activation file - id: getManualLicenseFile - uses: game-ci/unity-request-activation-file@v2 - with: - unityVersion: 2021.3.28f1 - # Upload artifact (Unity_v20XX.X.XXXX.alf) - - name: Expose as artifact - uses: actions/upload-artifact@v2 - with: - name: ${{ steps.getManualLicenseFile.outputs.filePath }} - path: ${{ steps.getManualLicenseFile.outputs.filePath }} diff --git a/.github/workflows/activation2022.yml b/.github/workflows/activation2022.yml deleted file mode 100644 index 758a6483..00000000 --- a/.github/workflows/activation2022.yml +++ /dev/null @@ -1,22 +0,0 @@ -name: Acquire activation file for 2022 - -on: - workflow_dispatch: {} - -jobs: - activation: - name: Request manual activation file 🔑 - runs-on: ubuntu-latest - steps: - # Request manual activation file - - name: Request manual activation file - id: getManualLicenseFile - uses: game-ci/unity-request-activation-file@v2 - with: - unityVersion: 2022.3.4f1 - # Upload artifact (Unity_v20XX.X.XXXX.alf) - - name: Expose as artifact - uses: actions/upload-artifact@v2 - with: - name: ${{ steps.getManualLicenseFile.outputs.filePath }} - path: ${{ steps.getManualLicenseFile.outputs.filePath }} diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index c9d3e877..549582c5 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -1,51 +1,67 @@ -# This is a basic workflow to help you get started with Actions +name: CI check for Unity 2020.3.x, 2021.3.x, 2022.3.x -name: CI - -# Controls when the action will run. Triggers the workflow on push or pull request -# events but only for the master branch on: pull_request: branches: - - master - - develop - -env: - UNITY_LICENSE: ${{ secrets.UNITY_LICENSE }} + - master + - beta/** jobs: - testAllModes: - name: Test in ${{ matrix.testMode }} on version ${{ matrix.unityVersion }} + test: + name: Test on Unity ${{ matrix.unityVersion }} runs-on: ubuntu-latest + strategy: fail-fast: false matrix: - projectPath: - - ./ unityVersion: - - 2020.1.13f1 - testMode: - - all -# - playmode -# - editmode + - 2020.3.48f1 + - 2021.3.42f1 + - 2022.3.42f1 + steps: - - uses: actions/checkout@v2 + # リãƒã‚¸ãƒˆãƒªã‚’ãƒã‚§ãƒƒã‚¯ã‚¢ã‚¦ãƒˆ + - name: Checkout repository + uses: actions/checkout@v4 with: - lfs: true - - uses: actions/cache@v1.1.0 + lfs: true # Large File StorageãŒå¿…è¦ãªå ´åˆã« true を指定 + + # Unity Test Runnerを実行 (エディットモードテスト) + - name: Run Edit Mode Tests + uses: game-ci/unity-test-runner@v4 + env: + UNITY_LICENSE: ${{ secrets.UNITY_LICENSE }} + UNITY_EMAIL: ${{ secrets.UNITY_EMAIL }} + UNITY_PASSWORD: ${{ secrets.UNITY_PASSWORD }} with: - path: ${{ matrix.projectPath }}/Library - key: Library-${{ matrix.projectPath }} - restore-keys: | - Library- - - uses: webbertakken/unity-test-runner@v1.4 - id: tests + projectPath: ./ + unityVersion: ${{ matrix.unityVersion }} + customParameters: -runTests -testPlatform editmode + artifactsPath: editmode-results + + # アーティファクトã®ã‚¢ãƒƒãƒ—ロード(エディットモード) + - name: Upload Edit Mode Test results for ${{ matrix.unityVersion }} + uses: actions/upload-artifact@v4 + with: + name: Edit Mode Test results for Unity ${{ matrix.unityVersion }} + path: editmode-results + + # Unity Test Runnerを実行 (プレイモードテスト) + - name: Run Play Mode Tests + uses: game-ci/unity-test-runner@v4 + env: + UNITY_LICENSE: ${{ secrets.UNITY_LICENSE }} + UNITY_EMAIL: ${{ secrets.UNITY_EMAIL }} + UNITY_PASSWORD: ${{ secrets.UNITY_PASSWORD }} with: - projectPath: ${{ matrix.projectPath }} + projectPath: ./ unityVersion: ${{ matrix.unityVersion }} - testMode: ${{ matrix.testMode }} - artifactsPath: ${{ matrix.testMode }}-artifacts - - uses: actions/upload-artifact@v1 + customParameters: -runTests -testPlatform playmode + artifactsPath: playmode-results + + # アーティファクトã®ã‚¢ãƒƒãƒ—ロード(プレイモード) + - name: Upload Play Mode Test results for ${{ matrix.unityVersion }} + uses: actions/upload-artifact@v4 with: - name: Test results for ${{ matrix.testMode }} - path: ${{ steps.tests.outputs.artifactsPath }} + name: Play Mode Test results for Unity ${{ matrix.unityVersion }} + path: playmode-results From d2b31f13b1497b678fd190f689eb83f728323d0f Mon Sep 17 00:00:00 2001 From: Ryodo Tanaka Date: Thu, 10 Oct 2024 00:01:59 +0900 Subject: [PATCH 03/15] Update to latest master README (#184) --- README.md | 98 +++++++++++++++++++++++++++++++++++++++++++++---------- 1 file changed, 81 insertions(+), 17 deletions(-) diff --git a/README.md b/README.md index cce04b8c..35aef143 100644 --- a/README.md +++ b/README.md @@ -1,15 +1,29 @@ -## UnitySensors +
-[![Acquire activation file](https://github.com/Field-Robotics-Japan/UnitySensorsROSAssets/workflows/Acquire%20activation%20file/badge.svg)](https://github.com/Field-Robotics-Japan/UnitySensorsROSAssets/actions?query=workflow%3A%22Acquire+activation+file%22) -[![CI](https://github.com/Field-Robotics-Japan/UnitySensorsROSAssets/workflows/CI/badge.svg)](https://github.com/Field-Robotics-Japan/UnitySensorsROSAssets/actions?query=workflow%3ACI) +# UnitySensors + +[![][github-release-shield]][github-release-link] +[![][external-unity-shield]][external-unity-link] +[![][external-ros-shield]][external-ros-link] +[![][github-workflow-shield]][github-workflow-link]
+[![][github-contributors-shield]][github-contributors-link] +[![][github-forks-shield]][github-forks-link] +[![][github-stars-shield]][github-stars-link] +[![][github-issues-shield]][github-issues-link] +[![][github-license-shield]][github-license-link] ![unity_sensors_ros_assets](.image/unity_sensors_ros_assets.gif) -## Overview -Robot sensor packages available on Unity. -You can communicate sensor info via ROS and ROS2 using ROSTCPConnector and ROSTCPEndpoint. +
+ +## 🔠Overview + +UnitySensos is a projet that regroup two Unity3D packages that allow you to **easly** use Unity3D as robotic simulation ! +There are several Prefab and Scene files available for testing each sensor. + +**1. UnitySensor** -The following sensors are added. +The following sensors are available inside : - Velodyne 3D LiDAR (Velodyne VLP-16, VLP-16-HiRes, VLP-32, HDL-32E, VLS-128) - Livox 3D LiDAR(Avia, Horizon, Mid40, Mid70, Tele, HAP, Mid360) @@ -20,24 +34,48 @@ The following sensors are added. - (GroundTruth) - (TF) -There are several Prefab and Scene files available for testing each sensor. +**2. UnitySensorROS** + +This package is responsible to make the link between sensor and ROS by serializing sensor raw data and sending to them to ROS using [ROS-TCP-Connector][external-RosTCPConnector-link] package. +To receive the data in ROS take a look at [ROS-TCP-Endpoint][external-RosTCPEndpoint-link]. + +## 🚀 Quick start -## Dependencies -- [RosTCPConnector](https://github.com/Unity-Technologies/ROS-TCP-Connector) (Appache 2.0 LICENSE) +### Inside Unity3D -## Package Installation (For using UnitySensors in your project) -1. Using Unity 2021.3 or later, open the Package Manager from `Window` -> `Package Manager`. +> \[!NOTE] +> +> Unitysensor is made for Unity 2020.3 or later + +1. Open the Package Manager from `Window` -> `Package Manager`. 2. In the Package Manager window, find and click the + button in the upper lefthand corner of the window. Select `Add package from git URL....` -3. Enter the git URL for the desired package. - 1. For the UnitySensors, enter `https://github.com/Field-Robotics-Japan/UnitySensors.git?path=/Assets/UnitySensors#v2.0.4`. - 2. For the UnitySensorsROS, enter `https://github.com/Field-Robotics-Japan/UnitySensors.git?path=/Assets/UnitySensorsROS#v2.0.4`. +3. Enter the git URL for the desired package. + 1. For the UnitySensors, enter `https://github.com/Field-Robotics-Japan/UnitySensors.git?path=/Assets/UnitySensors#v2.0.5`. + 2. For the UnitySensorsROS, enter `https://github.com/Field-Robotics-Japan/UnitySensors.git?path=/Assets/UnitySensorsROS#v2.0.5`. __Note: UnitySensorsROS does not contain UnitySensors.__ 4. Click `Add`. -## Documentation +### Inside ROS workspace + +1. Download lastest release of [ROS-TCP-Endpoint][external-RosTCPEndpoint-release-link]. +2. Build your workspace. +3. Launch ROS endpoint node. -## LICENSE +## 🤠Contributing + +
+ +A huge thank you to everyone who is helping to improve UnitySensors ! + +[![contributors badge][github-contributors-img]][github-contributors-link] + +
+ +## 🔗 Dependencies +- [ROS-TCP-Connector][external-RosTCPConnector-link] (Appache 2.0 LICENSE) + +## 📄 LICENSE Copyright [2020-2024] Ryodo Tanaka (groadpg@gmail.com) and Akiro Harada Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at @@ -45,3 +83,29 @@ Licensed under the Apache License, Version 2.0 (the "License"); you may not use http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. + + + +[external-unity-shield]: https://img.shields.io/badge/Unity3D-%3E%202020.3-blue?style=flat-square&logo=unity +[external-unity-link]: https://unity.com/ +[external-ros-shield]: https://img.shields.io/badge/ROS-1%7C2-blue?style=flat-square&logo=ros +[external-ros-link]: https://www.ros.org/ +[external-RosTCPConnector-link]: https://github.com/Unity-Technologies/ROS-TCP-Connector +[external-RosTCPEndpoint-link]: https://github.com/Unity-Technologies/ROS-TCP-Endpoint +[external-RosTCPEndpoint-release-link]: https://github.com/Unity-Technologies/ROS-TCP-Endpoint/releases +[github-workflow-shield]: https://img.shields.io/github/actions/workflow/status/Field-Robotics-Japan/UnitySensors/main.yml?style=flat-square&logo=github&label=CI%20check +[github-workflow-link]: https://github.com/Field-Robotics-Japan/UnitySensors/actions/workflows/main.yml +[github-contributors-img]: https://readme-contribs.as93.net/contributors/Field-Robotics-Japan/UnitySensors?avatarSize=40&shape=circle +[github-contributors-link]: https://github.com/Field-Robotics-Japan/UnitySensors/graphs/contributors +[github-contributors-shield]: https://img.shields.io/github/contributors/Field-Robotics-Japan/UnitySensors?color=B2FFA3&style=flat-square +[github-forks-link]: https://github.com/Field-Robotics-Japan/UnitySensors/network/members +[github-forks-shield]: https://img.shields.io/github/forks/Field-Robotics-Japan/UnitySensors?color=8ae8ff&style=flat-square +[github-issues-link]: https://github.com/Field-Robotics-Japan/UnitySensors/issues +[github-issues-shield]: https://img.shields.io/github/issues/Field-Robotics-Japan/UnitySensors?color=FFDBFA&style=flat-square +[github-license-link]: https://github.com/Field-Robotics-Japan/UnitySensors/blob/main/LICENSE +[github-license-shield]: https://img.shields.io/github/license/Field-Robotics-Japan/UnitySensors?color=FFADAD&style=flat-square +[github-stars-link]: https://github.com/Field-Robotics-Japan/UnitySensors/network/stargazers +[github-stars-shield]: https://img.shields.io/github/stars/Field-Robotics-Japan/UnitySensors?color=F9DC5F&style=flat-square +[github-release-link]: https://github.com/Field-Robotics-Japan/UnitySensors/releases +[github-release-shield]: https://img.shields.io/github/v/release/Field-Robotics-Japan/UnitySensors?color=9BF6FF&logo=github&style=flat-square + From c4e56f04cf2222b551aac4dceb14e5f5b84b0613 Mon Sep 17 00:00:00 2001 From: chy <1274653465@qq.com> Date: Sat, 16 Nov 2024 23:57:08 +0800 Subject: [PATCH 04/15] fixed depth camera texture pixel value in Color2DepthCamera.shader --- .../Camera/DepthCamera/DepthCameraSensor.cs | 10 +- .../Camera/DepthCamera/ITextureToPointsJob.cs | 5 +- .../Runtime/Shaders/Color2Depth.shader | 1 - .../Runtime/Shaders/Color2DepthCamera.shader | 48 ++++ .../Shaders/Color2DepthCamera.shader.meta | 9 + Packages/manifest.json | 12 +- Packages/packages-lock.json | 140 +++++----- ProjectSettings/InputManager.asset | 193 ++++++++++++++ ProjectSettings/MultiplayerManager.asset | 7 + ProjectSettings/PackageManagerSettings.asset | 9 +- ProjectSettings/ProjectSettings.asset | 239 ++++++++++++------ ProjectSettings/ProjectVersion.txt | 4 +- ProjectSettings/ShaderGraphSettings.asset | 16 ++ 13 files changed, 539 insertions(+), 154 deletions(-) create mode 100644 Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader create mode 100644 Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader.meta create mode 100644 ProjectSettings/MultiplayerManager.asset create mode 100644 ProjectSettings/ShaderGraphSettings.asset diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs index bc55695b..c75bb63b 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs @@ -59,9 +59,8 @@ protected override void Init() _texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBAFloat, false); - _mat = new Material(Shader.Find("UnitySensors/Color2Depth")); + _mat = new Material(Shader.Find("UnitySensors/Color2DepthCamera")); float f = m_camera.farClipPlane; - _mat.SetFloat("_F", f); SetupDirections(); SetupJob(); @@ -102,7 +101,7 @@ private void SetupJob() _textureToPointsJob = new ITextureToPointsJob() { - near= m_camera.nearClipPlane, + near = m_camera.nearClipPlane, far = m_camera.farClipPlane, directions = _directions, depthPixels = _texture.GetPixelData(0), @@ -127,7 +126,8 @@ protected override void UpdateSensor() private bool LoadTexture() { bool result = false; - AsyncGPUReadback.Request(_rt, 0, request => { + AsyncGPUReadback.Request(_rt, 0, request => + { if (request.hasError) { } @@ -154,7 +154,7 @@ protected override void OnSensorDestroy() private void OnRenderImage(RenderTexture source, RenderTexture dest) { - Graphics.Blit(source, dest, _mat); + Graphics.Blit(null, dest, _mat); } } } diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/ITextureToPointsJob.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/ITextureToPointsJob.cs index 31bdb2d0..f03908a2 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/ITextureToPointsJob.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/ITextureToPointsJob.cs @@ -27,13 +27,14 @@ public struct ITextureToPointsJob : IJobParallelFor public void Execute(int index) { - float distance = (1.0f - Mathf.Clamp01(depthPixels.AsReadOnly()[index].r)) * far; + float distance = depthPixels.AsReadOnly()[index].r * far; float distance_noised = distance + noises[index]; distance = (near < distance && distance < far && near < distance_noised && distance_noised < far) ? distance_noised : 0; + float radius = distance / directions[index].z; PointXYZ point = new PointXYZ() { - position = directions[index] * distance + position = directions[index] * radius }; points[index] = point; } diff --git a/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader b/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader index e9675741..39c63a8b 100644 --- a/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader +++ b/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader @@ -20,7 +20,6 @@ Shader "UnitySensors/Color2Depth" #include "UnityCG.cginc" sampler2D _CameraDepthTexture; - float4 _CameraDepthTexture_ST; float _F; float _Y_MIN; float _Y_MAX; diff --git a/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader b/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader new file mode 100644 index 00000000..2e691bf5 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader @@ -0,0 +1,48 @@ +Shader "UnitySensors/Color2DepthCamera" +{ + Properties + { + } + SubShader + { + Tags { "RenderType" = "Opaque" } + LOD 100 + + Pass + { + CGPROGRAM + #pragma vertex vert + #pragma fragment frag + #include "UnityCG.cginc" + + sampler2D _CameraDepthTexture; + + struct appdata + { + float4 vertex : POSITION; + float2 uv : TEXCOORD0; + }; + + struct v2f + { + float4 vertex : SV_POSITION; + float2 uv : TEXCOORD0; + }; + + v2f vert(appdata v) + { + v2f o; + o.vertex = UnityObjectToClipPos(v.vertex); + o.uv = v.uv; + return o; + } + + float4 frag(v2f i) : SV_Target + { + float depth01 = Linear01Depth(tex2D(_CameraDepthTexture, float2 (i.uv.x, i.uv.y )).r); + return float4(depth01, depth01, depth01, 1.0f); + } + ENDCG + } + } +} \ No newline at end of file diff --git a/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader.meta b/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader.meta new file mode 100644 index 00000000..d569162e --- /dev/null +++ b/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader.meta @@ -0,0 +1,9 @@ +fileFormatVersion: 2 +guid: 9f39b9c496a4e9f489f510e6d57c5126 +ShaderImporter: + externalObjects: {} + defaultTextures: [] + nonModifiableTextures: [] + userData: + assetBundleName: + assetBundleVariant: diff --git a/Packages/manifest.json b/Packages/manifest.json index df31cfd0..9fe6e90b 100644 --- a/Packages/manifest.json +++ b/Packages/manifest.json @@ -4,15 +4,13 @@ "com.unity.collab-proxy": "2.5.1", "com.unity.ide.rider": "3.0.31", "com.unity.ide.visualstudio": "2.0.22", - "com.unity.ide.vscode": "1.2.5", "com.unity.robotics.ros-tcp-connector": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git?path=/com.unity.robotics.ros-tcp-connector", "com.unity.robotics.visualizations": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git?path=/com.unity.robotics.visualizations", - "com.unity.test-framework": "1.1.33", - "com.unity.textmeshpro": "3.0.7", - "com.unity.timeline": "1.7.6", - "com.unity.toolchain.linux-x86_64": "2.0.4", - "com.unity.toolchain.win-x86_64-linux-x86_64": "2.0.6", - "com.unity.ugui": "1.0.0", + "com.unity.shadergraph": "16.0.6", + "com.unity.test-framework": "1.3.9", + "com.unity.timeline": "1.8.6", + "com.unity.ugui": "2.0.0", + "com.unity.modules.accessibility": "1.0.0", "com.unity.modules.ai": "1.0.0", "com.unity.modules.androidjni": "1.0.0", "com.unity.modules.animation": "1.0.0", diff --git a/Packages/packages-lock.json b/Packages/packages-lock.json index b119b7e8..f0a2dd12 100644 --- a/Packages/packages-lock.json +++ b/Packages/packages-lock.json @@ -8,21 +8,32 @@ "com.unity.mathematics": "1.2.1", "com.unity.modules.jsonserialize": "1.0.0" }, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" }, "com.unity.collab-proxy": { "version": "2.5.1", "depth": 0, "source": "registry", "dependencies": {}, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" + }, + "com.unity.collections": { + "version": "1.4.0", + "depth": 3, + "source": "registry", + "dependencies": { + "com.unity.burst": "1.6.6", + "com.unity.nuget.mono-cecil": "1.11.4", + "com.unity.test-framework": "1.1.31" + }, + "url": "https://packages.unity.cn" }, "com.unity.ext.nunit": { - "version": "1.0.6", + "version": "2.0.5", "depth": 1, "source": "registry", "dependencies": {}, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" }, "com.unity.ide.rider": { "version": "3.0.31", @@ -31,7 +42,7 @@ "dependencies": { "com.unity.ext.nunit": "1.0.6" }, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" }, "com.unity.ide.visualstudio": { "version": "2.0.22", @@ -40,21 +51,44 @@ "dependencies": { "com.unity.test-framework": "1.1.9" }, - "url": "https://packages.unity.com" - }, - "com.unity.ide.vscode": { - "version": "1.2.5", - "depth": 0, - "source": "registry", - "dependencies": {}, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" }, "com.unity.mathematics": { "version": "1.2.6", "depth": 1, "source": "registry", "dependencies": {}, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" + }, + "com.unity.nuget.mono-cecil": { + "version": "1.11.4", + "depth": 4, + "source": "registry", + "dependencies": {}, + "url": "https://packages.unity.cn" + }, + "com.unity.render-pipelines.core": { + "version": "16.0.6", + "depth": 1, + "source": "builtin", + "dependencies": { + "com.unity.mathematics": "1.2.4", + "com.unity.ugui": "2.0.0", + "com.unity.modules.physics": "1.0.0", + "com.unity.modules.terrain": "1.0.0", + "com.unity.modules.jsonserialize": "1.0.0", + "com.unity.rendering.light-transport": "1.0.0" + } + }, + "com.unity.rendering.light-transport": { + "version": "1.0.2", + "depth": 2, + "source": "builtin", + "dependencies": { + "com.unity.collections": "1.4.0", + "com.unity.mathematics": "1.2.4", + "com.unity.render-pipelines.core": "16.0.1" + } }, "com.unity.robotics.ros-tcp-connector": { "version": "https://github.com/Unity-Technologies/ROS-TCP-Connector.git?path=/com.unity.robotics.ros-tcp-connector", @@ -70,76 +104,47 @@ "dependencies": {}, "hash": "c27f00c6cf750d2d0564349b3039d19aa3925e7c" }, - "com.unity.sysroot": { - "version": "2.0.7", + "com.unity.searcher": { + "version": "4.9.2", "depth": 1, "source": "registry", "dependencies": {}, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" }, - "com.unity.sysroot.linux-x86_64": { - "version": "2.0.6", - "depth": 1, - "source": "registry", + "com.unity.shadergraph": { + "version": "16.0.6", + "depth": 0, + "source": "builtin", "dependencies": { - "com.unity.sysroot": "2.0.7" - }, - "url": "https://packages.unity.com" + "com.unity.render-pipelines.core": "16.0.6", + "com.unity.searcher": "4.9.2" + } }, "com.unity.test-framework": { - "version": "1.1.33", + "version": "1.3.9", "depth": 0, "source": "registry", "dependencies": { - "com.unity.ext.nunit": "1.0.6", + "com.unity.ext.nunit": "2.0.3", "com.unity.modules.imgui": "1.0.0", "com.unity.modules.jsonserialize": "1.0.0" }, - "url": "https://packages.unity.com" - }, - "com.unity.textmeshpro": { - "version": "3.0.7", - "depth": 0, - "source": "registry", - "dependencies": { - "com.unity.ugui": "1.0.0" - }, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" }, "com.unity.timeline": { - "version": "1.7.6", + "version": "1.8.6", "depth": 0, "source": "registry", "dependencies": { - "com.unity.modules.audio": "1.0.0", "com.unity.modules.director": "1.0.0", "com.unity.modules.animation": "1.0.0", + "com.unity.modules.audio": "1.0.0", "com.unity.modules.particlesystem": "1.0.0" }, - "url": "https://packages.unity.com" - }, - "com.unity.toolchain.linux-x86_64": { - "version": "2.0.4", - "depth": 0, - "source": "registry", - "dependencies": { - "com.unity.sysroot": "2.0.5", - "com.unity.sysroot.linux-x86_64": "2.0.4" - }, - "url": "https://packages.unity.com" - }, - "com.unity.toolchain.win-x86_64-linux-x86_64": { - "version": "2.0.6", - "depth": 0, - "source": "registry", - "dependencies": { - "com.unity.sysroot": "2.0.7", - "com.unity.sysroot.linux-x86_64": "2.0.6" - }, - "url": "https://packages.unity.com" + "url": "https://packages.unity.cn" }, "com.unity.ugui": { - "version": "1.0.0", + "version": "2.0.0", "depth": 0, "source": "builtin", "dependencies": { @@ -147,6 +152,12 @@ "com.unity.modules.imgui": "1.0.0" } }, + "com.unity.modules.accessibility": { + "version": "1.0.0", + "depth": 0, + "source": "builtin", + "dependencies": {} + }, "com.unity.modules.ai": { "version": "1.0.0", "depth": 0, @@ -194,6 +205,12 @@ "com.unity.modules.animation": "1.0.0" } }, + "com.unity.modules.hierarchycore": { + "version": "1.0.0", + "depth": 1, + "source": "builtin", + "dependencies": {} + }, "com.unity.modules.imageconversion": { "version": "1.0.0", "depth": 0, @@ -282,7 +299,8 @@ "dependencies": { "com.unity.modules.ui": "1.0.0", "com.unity.modules.imgui": "1.0.0", - "com.unity.modules.jsonserialize": "1.0.0" + "com.unity.modules.jsonserialize": "1.0.0", + "com.unity.modules.hierarchycore": "1.0.0" } }, "com.unity.modules.umbra": { diff --git a/ProjectSettings/InputManager.asset b/ProjectSettings/InputManager.asset index 17c8f538..6a65192d 100644 --- a/ProjectSettings/InputManager.asset +++ b/ProjectSettings/InputManager.asset @@ -293,3 +293,196 @@ InputManager: type: 0 axis: 0 joyNum: 0 + - serializedVersion: 3 + m_Name: Enable Debug Button 1 + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: left ctrl + altNegativeButton: + altPositiveButton: joystick button 8 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Enable Debug Button 2 + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: backspace + altNegativeButton: + altPositiveButton: joystick button 9 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Reset + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: left alt + altNegativeButton: + altPositiveButton: joystick button 1 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Next + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: page down + altNegativeButton: + altPositiveButton: joystick button 5 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Previous + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: page up + altNegativeButton: + altPositiveButton: joystick button 4 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Validate + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: return + altNegativeButton: + altPositiveButton: joystick button 0 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Persistent + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: right shift + altNegativeButton: + altPositiveButton: joystick button 2 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Multiplier + descriptiveName: + descriptiveNegativeName: + negativeButton: + positiveButton: left shift + altNegativeButton: + altPositiveButton: joystick button 3 + gravity: 0 + dead: 0 + sensitivity: 0 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Horizontal + descriptiveName: + descriptiveNegativeName: + negativeButton: left + positiveButton: right + altNegativeButton: + altPositiveButton: + gravity: 1000 + dead: 0.001 + sensitivity: 1000 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Vertical + descriptiveName: + descriptiveNegativeName: + negativeButton: down + positiveButton: up + altNegativeButton: + altPositiveButton: + gravity: 1000 + dead: 0.001 + sensitivity: 1000 + snap: 0 + invert: 0 + type: 0 + axis: 0 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Vertical + descriptiveName: + descriptiveNegativeName: + negativeButton: down + positiveButton: up + altNegativeButton: + altPositiveButton: + gravity: 1000 + dead: 0.001 + sensitivity: 1000 + snap: 0 + invert: 0 + type: 2 + axis: 6 + joyNum: 0 + - serializedVersion: 3 + m_Name: Debug Horizontal + descriptiveName: + descriptiveNegativeName: + negativeButton: left + positiveButton: right + altNegativeButton: + altPositiveButton: + gravity: 1000 + dead: 0.001 + sensitivity: 1000 + snap: 0 + invert: 0 + type: 2 + axis: 5 + joyNum: 0 + m_UsePhysicalKeys: 1 diff --git a/ProjectSettings/MultiplayerManager.asset b/ProjectSettings/MultiplayerManager.asset new file mode 100644 index 00000000..8073753a --- /dev/null +++ b/ProjectSettings/MultiplayerManager.asset @@ -0,0 +1,7 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!655991488 &1 +MultiplayerManager: + m_ObjectHideFlags: 0 + m_EnableMultiplayerRoles: 0 + m_ActiveMultiplayerRole: 0 diff --git a/ProjectSettings/PackageManagerSettings.asset b/ProjectSettings/PackageManagerSettings.asset index dec5942a..f635c40d 100644 --- a/ProjectSettings/PackageManagerSettings.asset +++ b/ProjectSettings/PackageManagerSettings.asset @@ -13,15 +13,16 @@ MonoBehaviour: m_Name: m_EditorClassIdentifier: m_EnablePreReleasePackages: 0 - m_EnablePackageDependencies: 0 m_AdvancedSettingsExpanded: 1 m_ScopedRegistriesSettingsExpanded: 1 m_SeeAllPackageVersions: 0 + m_DismissPreviewPackagesInUse: 0 oneTimeWarningShown: 0 + oneTimeDeprecatedPopUpShown: 1 m_Registries: - m_Id: main m_Name: - m_Url: https://packages.unity.com + m_Url: https://packages.unity.cn m_Scopes: [] m_IsDefault: 1 m_Capabilities: 7 @@ -31,6 +32,6 @@ MonoBehaviour: m_RegistryInfoDraft: m_Modified: 0 m_ErrorMessage: - m_UserModificationsInstanceId: -826 - m_OriginalInstanceId: -828 + m_UserModificationsInstanceId: -872 + m_OriginalInstanceId: -874 m_LoadAssets: 0 diff --git a/ProjectSettings/ProjectSettings.asset b/ProjectSettings/ProjectSettings.asset index 9b337db7..a789fe75 100644 --- a/ProjectSettings/ProjectSettings.asset +++ b/ProjectSettings/ProjectSettings.asset @@ -3,7 +3,7 @@ --- !u!129 &1 PlayerSettings: m_ObjectHideFlags: 0 - serializedVersion: 20 + serializedVersion: 27 productGUID: 862468181e5ecf14b90e367b9ff0e061 AndroidProfiler: 0 AndroidFilterTouchesWhenObscured: 0 @@ -47,13 +47,17 @@ PlayerSettings: defaultScreenWidthWeb: 960 defaultScreenHeightWeb: 600 m_StereoRenderingPath: 0 - m_ActiveColorSpace: 0 + m_ActiveColorSpace: 1 + unsupportedMSAAFallback: 0 + m_SpriteBatchVertexThreshold: 300 m_MTRendering: 1 + mipStripping: 0 + numberOfMipsStripped: 0 + numberOfMipsStrippedPerMipmapLimitGroup: {} m_StackTraceTypes: 010000000100000001000000010000000100000001000000 iosShowActivityIndicatorOnLoading: -1 androidShowActivityIndicatorOnLoading: -1 iosUseCustomAppBackgroundBehavior: 0 - iosAllowHTTPDownload: 1 allowedAutorotateToPortrait: 1 allowedAutorotateToPortraitUpsideDown: 1 allowedAutorotateToLandscapeRight: 1 @@ -66,6 +70,14 @@ PlayerSettings: androidRenderOutsideSafeArea: 1 androidUseSwappy: 0 androidBlitType: 0 + androidResizableWindow: 0 + androidDefaultWindowWidth: 1920 + androidDefaultWindowHeight: 1080 + androidMinimumWindowWidth: 400 + androidMinimumWindowHeight: 300 + androidFullscreenMode: 1 + androidAutoRotationBehavior: 1 + androidApplicationEntry: 1 defaultIsNativeResolution: 1 macRetinaSupport: 1 runInBackground: 1 @@ -77,6 +89,7 @@ PlayerSettings: hideHomeButton: 0 submitAnalytics: 1 usePlayerLog: 1 + dedicatedServerOptimizations: 0 bakeCollisionMeshes: 0 forceSingleInstance: 0 useFlipModelSwapchain: 1 @@ -84,6 +97,7 @@ PlayerSettings: useMacAppStoreValidation: 0 macAppStoreCategory: public.app-category.games gpuSkinning: 1 + meshDeformation: 2 xboxPIXTextureCapture: 0 xboxEnableAvatar: 0 xboxEnableKinect: 0 @@ -111,14 +125,18 @@ PlayerSettings: switchNVNShaderPoolsGranularity: 33554432 switchNVNDefaultPoolsGranularity: 16777216 switchNVNOtherPoolsGranularity: 16777216 + switchGpuScratchPoolGranularity: 2097152 + switchAllowGpuScratchShrinking: 0 + switchNVNMaxPublicTextureIDCount: 0 + switchNVNMaxPublicSamplerIDCount: 0 + switchMaxWorkerMultiple: 8 + switchNVNGraphicsFirmwareMemory: 32 vulkanNumSwapchainBuffers: 3 vulkanEnableSetSRGBWrite: 0 - m_SupportedAspectRatios: - 4:3: 1 - 5:4: 1 - 16:10: 1 - 16:9: 1 - Others: 1 + vulkanEnablePreTransform: 0 + vulkanEnableLateAcquireNextImage: 0 + vulkanEnableCommandBufferRecycling: 1 + loadStoreDebugModeEnabled: 0 bundleVersion: 0.1 preloadedAssets: [] metroInputSource: 0 @@ -127,45 +145,30 @@ PlayerSettings: xboxOneDisableKinectGpuReservation: 1 xboxOneEnable7thCore: 1 vrSettings: - cardboard: - depthFormat: 0 - enableTransitionView: 0 - daydream: - depthFormat: 0 - useSustainedPerformanceMode: 0 - enableVideoLayer: 0 - useProtectedVideoMemory: 0 - minimumSupportedHeadTracking: 0 - maximumSupportedHeadTracking: 1 - hololens: - depthFormat: 1 - depthBufferSharingEnabled: 1 - lumin: - depthFormat: 0 - frameTiming: 2 - enableGLCache: 0 - glCacheMaxBlobSize: 524288 - glCacheMaxFileSize: 8388608 - oculus: - sharedDepthBuffer: 1 - dashSupport: 1 - lowOverheadMode: 0 - protectedContext: 0 - v2Signing: 1 enable360StereoCapture: 0 isWsaHolographicRemotingEnabled: 0 enableFrameTimingStats: 0 + enableOpenGLProfilerGPURecorders: 1 + allowHDRDisplaySupport: 0 useHDRDisplay: 0 - D3DHDRBitDepth: 0 + hdrBitDepth: 0 m_ColorGamuts: 00000000 targetPixelDensity: 30 resolutionScalingMode: 0 + resetResolutionOnWindowResize: 0 androidSupportedAspectRatio: 1 androidMaxAspectRatio: 2.1 - applicationIdentifier: {} - buildNumber: {} + androidMinAspectRatio: 1 + applicationIdentifier: + Standalone: com.DefaultCompany.unit04-unity + buildNumber: + Bratwurst: 0 + Standalone: 0 + iPhone: 0 + tvOS: 0 + overrideDefaultApplicationIdentifier: 0 AndroidBundleVersionCode: 1 - AndroidMinSdkVersion: 19 + AndroidMinSdkVersion: 23 AndroidTargetSdkVersion: 0 AndroidPreferredInstallLocation: 1 aotOptions: @@ -175,37 +178,24 @@ PlayerSettings: ForceInternetPermission: 0 ForceSDCardPermission: 0 CreateWallpaper: 0 - APKExpansionFiles: 0 + androidSplitApplicationBinary: 0 keepLoadedShadersAlive: 0 StripUnusedMeshComponents: 1 + strictShaderVariantMatching: 0 VertexChannelCompressionMask: 4054 iPhoneSdkVersion: 988 - iOSTargetOSVersionString: 10.0 + iOSTargetOSVersionString: 13.0 tvOSSdkVersion: 0 tvOSRequireExtendedGameController: 0 - tvOSTargetOSVersionString: 10.0 + tvOSTargetOSVersionString: 13.0 + bratwurstSdkVersion: 0 + bratwurstTargetOSVersionString: 13.0 uIPrerenderedIcon: 0 uIRequiresPersistentWiFi: 0 uIRequiresFullScreen: 1 uIStatusBarHidden: 1 uIExitOnSuspend: 0 uIStatusBarStyle: 0 - iPhoneSplashScreen: {fileID: 0} - iPhoneHighResSplashScreen: {fileID: 0} - iPhoneTallHighResSplashScreen: {fileID: 0} - iPhone47inSplashScreen: {fileID: 0} - iPhone55inPortraitSplashScreen: {fileID: 0} - iPhone55inLandscapeSplashScreen: {fileID: 0} - iPhone58inPortraitSplashScreen: {fileID: 0} - iPhone58inLandscapeSplashScreen: {fileID: 0} - iPadPortraitSplashScreen: {fileID: 0} - iPadHighResPortraitSplashScreen: {fileID: 0} - iPadLandscapeSplashScreen: {fileID: 0} - iPadHighResLandscapeSplashScreen: {fileID: 0} - iPhone65inPortraitSplashScreen: {fileID: 0} - iPhone65inLandscapeSplashScreen: {fileID: 0} - iPhone61inPortraitSplashScreen: {fileID: 0} - iPhone61inLandscapeSplashScreen: {fileID: 0} appleTVSplashScreen: {fileID: 0} appleTVSplashScreen2x: {fileID: 0} tvOSSmallIconLayers: [] @@ -233,32 +223,48 @@ PlayerSettings: iOSLaunchScreeniPadFillPct: 100 iOSLaunchScreeniPadSize: 100 iOSLaunchScreeniPadCustomXibPath: - iOSUseLaunchScreenStoryboard: 0 iOSLaunchScreenCustomStoryboardPath: + iOSLaunchScreeniPadCustomStoryboardPath: iOSDeviceRequirements: [] iOSURLSchemes: [] + macOSURLSchemes: [] iOSBackgroundModes: 0 iOSMetalForceHardShadows: 0 metalEditorSupport: 1 metalAPIValidation: 1 iOSRenderExtraFrameOnPause: 0 + iosCopyPluginsCodeInsteadOfSymlink: 0 appleDeveloperTeamID: iOSManualSigningProvisioningProfileID: tvOSManualSigningProvisioningProfileID: + bratwurstManualSigningProvisioningProfileID: iOSManualSigningProvisioningProfileType: 0 tvOSManualSigningProvisioningProfileType: 0 + bratwurstManualSigningProvisioningProfileType: 0 appleEnableAutomaticSigning: 0 iOSRequireARKit: 0 iOSAutomaticallyDetectAndAddCapabilities: 1 appleEnableProMotion: 0 + shaderPrecisionModel: 0 clonedFromGUID: c0afd0d1d80e3634a9dac47e8a0426ea templatePackageId: com.unity.template.3d@4.2.8 templateDefaultScene: Assets/Scenes/SampleScene.unity + useCustomMainManifest: 0 + useCustomLauncherManifest: 0 + useCustomMainGradleTemplate: 0 + useCustomLauncherGradleManifest: 0 + useCustomBaseGradleTemplate: 0 + useCustomGradlePropertiesTemplate: 0 + useCustomGradleSettingsTemplate: 0 + useCustomProguardFile: 0 AndroidTargetArchitectures: 1 + AndroidTargetDevices: 0 AndroidSplashScreenScale: 0 androidSplashScreen: {fileID: 0} AndroidKeystoreName: AndroidKeyaliasName: + AndroidEnableArmv9SecurityFeatures: 0 + AndroidEnableArm64MTE: 0 AndroidBuildApkPerCpuArchitecture: 0 AndroidTVCompatibility: 0 AndroidIsGame: 1 @@ -271,8 +277,12 @@ PlayerSettings: height: 180 banner: {fileID: 0} androidGamepadSupportLevel: 0 + chromeosInputEmulation: 1 + AndroidMinifyRelease: 0 + AndroidMinifyDebug: 0 AndroidValidateAppBundleSize: 1 AndroidAppBundleSizeToValidate: 150 + AndroidReportGooglePlayAppDependencies: 1 m_BuildTargetIcons: [] m_BuildTargetPlatformIcons: [] m_BuildTargetBatching: @@ -291,6 +301,7 @@ PlayerSettings: - m_BuildTarget: WebGL m_StaticBatching: 0 m_DynamicBatching: 0 + m_BuildTargetShaderSettings: [] m_BuildTargetGraphicsJobs: - m_BuildTarget: MacStandaloneSupport m_GraphicsJobs: 0 @@ -326,13 +337,13 @@ PlayerSettings: m_BuildTargetGraphicsAPIs: - m_BuildTarget: AndroidPlayer m_APIs: 150000000b000000 - m_Automatic: 0 + m_Automatic: 1 - m_BuildTarget: iOSSupport m_APIs: 10000000 m_Automatic: 1 - m_BuildTarget: AppleTVSupport m_APIs: 10000000 - m_Automatic: 0 + m_Automatic: 1 - m_BuildTarget: WebGLSupport m_APIs: 0b000000 m_Automatic: 1 @@ -342,6 +353,8 @@ PlayerSettings: m_Devices: - Oculus - OpenVR + m_DefaultShaderChunkSizeInMB: 16 + m_DefaultShaderChunkCount: 0 openGLRequireES31: 0 openGLRequireES31AEP: 0 openGLRequireES32: 0 @@ -351,7 +364,11 @@ PlayerSettings: iPhone: 1 tvOS: 1 m_BuildTargetGroupLightmapEncodingQuality: [] + m_BuildTargetGroupHDRCubemapEncodingQuality: [] m_BuildTargetGroupLightmapSettings: [] + m_BuildTargetGroupLoadStoreDebugModeSettings: [] + m_BuildTargetNormalMapEncoding: [] + m_BuildTargetDefaultTextureCompressionFormat: [] playModeTestRunnerEnabled: 0 runPlayModeTestAsEditModeTest: 0 actionOnDotNetUnhandledException: 1 @@ -361,14 +378,20 @@ PlayerSettings: cameraUsageDescription: locationUsageDescription: microphoneUsageDescription: + bluetoothUsageDescription: + macOSTargetOSVersion: 10.13.0 + switchNMETAOverride: switchNetLibKey: switchSocketMemoryPoolSize: 6144 switchSocketAllocatorPoolSize: 128 switchSocketConcurrencyLimit: 14 switchScreenResolutionBehavior: 2 switchUseCPUProfiler: 0 + switchEnableFileSystemTrace: 0 + switchLTOSetting: 0 switchApplicationID: 0x01004b9000490000 switchNSODependencies: + switchCompilerFlags: switchTitleNames_0: switchTitleNames_1: switchTitleNames_2: @@ -384,6 +407,7 @@ PlayerSettings: switchTitleNames_12: switchTitleNames_13: switchTitleNames_14: + switchTitleNames_15: switchPublisherNames_0: switchPublisherNames_1: switchPublisherNames_2: @@ -399,6 +423,7 @@ PlayerSettings: switchPublisherNames_12: switchPublisherNames_13: switchPublisherNames_14: + switchPublisherNames_15: switchIcons_0: {fileID: 0} switchIcons_1: {fileID: 0} switchIcons_2: {fileID: 0} @@ -414,6 +439,7 @@ PlayerSettings: switchIcons_12: {fileID: 0} switchIcons_13: {fileID: 0} switchIcons_14: {fileID: 0} + switchIcons_15: {fileID: 0} switchSmallIcons_0: {fileID: 0} switchSmallIcons_1: {fileID: 0} switchSmallIcons_2: {fileID: 0} @@ -429,6 +455,7 @@ PlayerSettings: switchSmallIcons_12: {fileID: 0} switchSmallIcons_13: {fileID: 0} switchSmallIcons_14: {fileID: 0} + switchSmallIcons_15: {fileID: 0} switchManualHTML: switchAccessibleURLs: switchLegalInformation: @@ -438,7 +465,6 @@ PlayerSettings: switchReleaseVersion: 0 switchDisplayVersion: 1.0.0 switchStartupUserAccount: 0 - switchTouchScreenUsage: 0 switchSupportedLanguagesMask: 0 switchLogoType: 0 switchApplicationErrorCodeCategory: @@ -480,6 +506,7 @@ PlayerSettings: switchNativeFsCacheSize: 32 switchIsHoldTypeHorizontal: 0 switchSupportedNpadCount: 8 + switchEnableTouchScreen: 1 switchSocketConfigEnabled: 0 switchTcpInitialSendBufferSize: 32 switchTcpInitialReceiveBufferSize: 64 @@ -490,7 +517,13 @@ PlayerSettings: switchSocketBufferEfficiency: 4 switchSocketInitializeEnabled: 1 switchNetworkInterfaceManagerInitializeEnabled: 1 - switchPlayerConnectionEnabled: 1 + switchDisableHTCSPlayerConnection: 0 + switchUseNewStyleFilepaths: 1 + switchUseLegacyFmodPriorities: 0 + switchUseMicroSleepForYield: 1 + switchEnableRamDiskSupport: 0 + switchMicroSleepForYieldTime: 25 + switchRamDiskSpaceSize: 12 ps4NPAgeRating: 12 ps4NPTitleSecret: ps4NPTrophyPackPath: @@ -517,6 +550,7 @@ PlayerSettings: ps4ShareFilePath: ps4ShareOverlayImagePath: ps4PrivacyGuardImagePath: + ps4ExtraSceSysFile: ps4NPtitleDatPath: ps4RemotePlayKeyAssignment: -1 ps4RemotePlayKeyMappingDir: @@ -559,6 +593,9 @@ PlayerSettings: ps4disableAutoHideSplash: 0 ps4videoRecordingFeaturesUsed: 0 ps4contentSearchFeaturesUsed: 0 + ps4CompatibilityPS5: 0 + ps4AllowPS5Detection: 0 + ps4GPU800MHz: 1 ps4attribEyeToEyeDistanceSettingVR: 0 ps4IncludedModules: [] ps4attribVROutputEnabled: 0 @@ -570,6 +607,7 @@ PlayerSettings: webGLMemorySize: 16 webGLExceptionSupport: 1 webGLNameFilesAsHashes: 0 + webGLShowDiagnostics: 0 webGLDataCaching: 1 webGLDebugSymbols: 0 webGLEmscriptenArgs: @@ -578,21 +616,66 @@ PlayerSettings: webGLAnalyzeBuildSize: 0 webGLUseEmbeddedResources: 0 webGLCompressionFormat: 1 + webGLWasmArithmeticExceptions: 0 webGLLinkerTarget: 1 webGLThreadsSupport: 0 - webGLWasmStreaming: 0 - scriptingDefineSymbols: {} + webGLDecompressionFallback: 0 + webGLInitialMemorySize: 32 + webGLMaximumMemorySize: 2048 + webGLMemoryGrowthMode: 2 + webGLMemoryLinearGrowthStep: 16 + webGLMemoryGeometricGrowthStep: 0.2 + webGLMemoryGeometricGrowthCap: 96 + webGLEnableWebGPU: 0 + webGLPowerPreference: 2 + webGLWebAssemblyTable: 0 + webGLWebAssemblyBigInt: 0 + webGLCloseOnQuit: 0 + scriptingDefineSymbols: + Android: UNITY_POST_PROCESSING_STACK_V2 + Bratwurst: UNITY_POST_PROCESSING_STACK_V2 + EmbeddedLinux: UNITY_POST_PROCESSING_STACK_V2 + GameCoreXboxOne: UNITY_POST_PROCESSING_STACK_V2 + Nintendo Switch: UNITY_POST_PROCESSING_STACK_V2 + PS4: UNITY_POST_PROCESSING_STACK_V2 + PS5: UNITY_POST_PROCESSING_STACK_V2 + QNX: UNITY_POST_PROCESSING_STACK_V2 + Standalone: UNITY_POST_PROCESSING_STACK_V2;ROS2 + WebGL: UNITY_POST_PROCESSING_STACK_V2 + XboxOne: UNITY_POST_PROCESSING_STACK_V2 + tvOS: UNITY_POST_PROCESSING_STACK_V2 + additionalCompilerArguments: {} platformArchitecture: {} - scriptingBackend: {} + scriptingBackend: + Android: 0 il2cppCompilerConfiguration: {} - managedStrippingLevel: {} + il2cppCodeGeneration: {} + il2cppStacktraceInformation: {} + managedStrippingLevel: + Android: 1 + Bratwurst: 1 + EmbeddedLinux: 1 + GameCoreScarlett: 1 + GameCoreXboxOne: 1 + Nintendo Switch: 1 + PS4: 1 + PS5: 1 + QNX: 1 + WebGL: 1 + Windows Store Apps: 1 + XboxOne: 1 + iPhone: 1 + tvOS: 1 incrementalIl2cppBuild: {} + suppressCommonWarnings: 1 allowUnsafeCode: 0 + useDeterministicCompilation: 1 additionalIl2CppArgs: scriptingRuntimeVersion: 1 gcIncremental: 0 gcWBarrierValidation: 0 apiCompatibilityLevelPerPlatform: {} + editorAssembliesCompatibilityLevel: 1 m_RenderingPath: 1 m_MobileRenderingPath: 1 metroPackageName: Template_3D @@ -617,11 +700,13 @@ PlayerSettings: metroSplashScreenBackgroundColor: {r: 0.12941177, g: 0.17254902, b: 0.21568628, a: 1} metroSplashScreenUseBackgroundColor: 0 + syncCapabilities: 0 platformCapabilities: {} metroTargetDeviceFamilies: {} metroFTAName: metroFTAFileTypes: [] metroProtocolName: + vcxProjDefaultLanguage: XboxOneProductId: XboxOneUpdateKey: XboxOneSandboxId: @@ -640,6 +725,7 @@ PlayerSettings: XboxOneCapability: [] XboxOneGameRating: {} XboxOneIsContentPackage: 0 + XboxOneEnhancedXboxCompatibilityMode: 0 XboxOneEnableGPUVariability: 1 XboxOneSockets: {} XboxOneSplashScreen: {fileID: 0} @@ -648,10 +734,7 @@ PlayerSettings: XboxOneXTitleMemory: 8 XboxOneOverrideIdentityName: XboxOneOverrideIdentityPublisher: - vrEditorSettings: - daydream: - daydreamIconForeground: {fileID: 0} - daydreamIconBackground: {fileID: 0} + vrEditorSettings: {} cloudServicesEnabled: UNet: 1 luminIcon: @@ -665,12 +748,24 @@ PlayerSettings: luminVersion: m_VersionCode: 1 m_VersionName: + hmiPlayerDataPath: + hmiForceSRGBBlit: 0 + embeddedLinuxEnableGamepadInput: 0 + hmiCpuConfiguration: + hmiLogStartupTiming: 0 + qnxGraphicConfPath: apiCompatibilityLevel: 6 + captureStartupLogs: {} + activeInputHandler: 0 + windowsGamepadBackendHint: 0 cloudProjectId: framebufferDepthMemorylessMode: 0 + qualitySettingsNames: [] projectName: organizationId: cloudEnabled: 0 - enableNativePlatformBackendsForNewInputSystem: 0 - disableOldInputManagerSupport: 0 legacyClampBlendShapeWeights: 0 + hmiLoadingImage: {fileID: 0} + platformRequiresReadableAssets: 0 + virtualTexturingSupportEnabled: 0 + insecureHttpOption: 0 diff --git a/ProjectSettings/ProjectVersion.txt b/ProjectSettings/ProjectVersion.txt index ca0a6795..cf8f572c 100644 --- a/ProjectSettings/ProjectVersion.txt +++ b/ProjectSettings/ProjectVersion.txt @@ -1,2 +1,2 @@ -m_EditorVersion: 2022.3.49f1 -m_EditorVersionWithRevision: 2022.3.49f1 (4dae1bb8668d) +m_EditorVersion: 2023.2.20f1c1 +m_EditorVersionWithRevision: 2023.2.20f1c1 (ceda3f59bbc9) diff --git a/ProjectSettings/ShaderGraphSettings.asset b/ProjectSettings/ShaderGraphSettings.asset new file mode 100644 index 00000000..a11ed582 --- /dev/null +++ b/ProjectSettings/ShaderGraphSettings.asset @@ -0,0 +1,16 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!114 &1 +MonoBehaviour: + m_ObjectHideFlags: 53 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 0} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: de02f9e1d18f588468e474319d09a723, type: 3} + m_Name: + m_EditorClassIdentifier: + customInterpolatorErrorThreshold: 32 + customInterpolatorWarningThreshold: 16 From 7ff9315bd9cd9325a4cee8868307cf59311c53c6 Mon Sep 17 00:00:00 2001 From: chy <1274653465@qq.com> Date: Sun, 17 Nov 2024 14:55:57 +0800 Subject: [PATCH 05/15] Rewrite the Color2DepthCamera shader with Shader Graph to make the depth camera support UPR/HDRP; load the shader via a material reference and create the corresponding material; rename the Color2Depth shader to DepthBufferLidar shader and use it for DepthBufferLidar; Change asmdef to exclude Editor scripts when packaging --- .../Editor/UnitySensorsEditor.asmdef | 4 +- .../Runtime/Materials/CustomMaterials.meta | 8 + .../UnitySensors_DepthBufferLidar.mat | 34 ++ .../UnitySensors_DepthBufferLidar.mat.meta | 8 + .../UnitySensors_PointCloudXYZ.mat | 36 ++ .../UnitySensors_PointCloudXYZ.mat.meta | 8 + .../UnitySensors_PointCloudXYZI.mat | 36 ++ .../UnitySensors_PointCloudXYZI.mat.meta | 8 + .../UnitySensors_PointCloudXYZRGB.mat | 36 ++ .../UnitySensors_PointCloudXYZRGB.mat.meta | 8 + .../Runtime/Prefabs/Camera/DepthCamera.prefab | 30 +- .../Runtime/Prefabs/Camera/RGBCamera.prefab | 14 +- .../Runtime/Prefabs/Camera/RGBDCamera.prefab | 14 +- .../Velodyne/VLS-128_with_DepthBuffer.prefab | 20 +- .../Camera/DepthCamera/DepthCameraSensor.cs | 9 +- .../RGBDCamera/ITextureToColorPointsJob.cs | 7 +- .../Camera/RGBDCamera/RGBDCameraSensor.cs | 14 +- .../DepthBufferLiDARSensor.cs | 8 +- .../DepthBufferLiDAR/ITextureToPointsJob.cs | 3 +- .../RaycastLiDAR/IUpdateRaycastCommandsJob.cs | 1 + .../Scripts/Utils/Camera/Color2Depth.cs | 8 +- .../Utils/PointCloud/PointUtilities.cs | 3 + .../Runtime/Shaders/Color2Depth.shader.meta | 10 - .../Runtime/Shaders/Color2DepthCamera.shader | 48 --- ...r2Depth.shader => DepthBufferLidar.shader} | 5 +- ...ader.meta => DepthBufferLidar.shader.meta} | 0 .../Runtime/Shaders/DepthCamera.shadergraph | 377 ++++++++++++++++++ .../Shaders/DepthCamera.shadergraph.meta | 10 + .../Runtime/Shaders/PointCloudXYZ.shader | 1 + .../Runtime/Shaders/PointCloudXYZI.shader | 1 + .../Runtime/Shaders/PointCloudXYZRGB.shader | 1 + .../Samples/Camera/Demo_DepthCamera.unity | 95 ++++- .../Samples/Camera/Demo_RGBCamera.unity | 75 +++- .../Editor/UnitySensorsROSEditor.asmdef | 4 +- .../Prefabs/Camera/DepthCamera_ros.prefab | 14 +- .../Prefabs/Camera/RGBCamera_ros.prefab | 14 +- .../Prefabs/Camera/RGBDCamera_ros.prefab | 26 +- ProjectSettings/EditorBuildSettings.asset | 6 +- ProjectSettings/GraphicsSettings.asset | 17 +- 39 files changed, 864 insertions(+), 157 deletions(-) create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials.meta create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat.meta create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat.meta create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat.meta create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat create mode 100644 Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat.meta delete mode 100644 Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader.meta delete mode 100644 Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader rename Assets/UnitySensors/Runtime/Shaders/{Color2Depth.shader => DepthBufferLidar.shader} (90%) rename Assets/UnitySensors/Runtime/Shaders/{Color2DepthCamera.shader.meta => DepthBufferLidar.shader.meta} (100%) create mode 100644 Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph create mode 100644 Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph.meta diff --git a/Assets/UnitySensors/Editor/UnitySensorsEditor.asmdef b/Assets/UnitySensors/Editor/UnitySensorsEditor.asmdef index 1ffa9e28..a6010e3b 100644 --- a/Assets/UnitySensors/Editor/UnitySensorsEditor.asmdef +++ b/Assets/UnitySensors/Editor/UnitySensorsEditor.asmdef @@ -5,7 +5,9 @@ "GUID:d8b63aba1907145bea998dd612889d6b", "GUID:e9a473e6ad03eae4a89800bf81bd1594" ], - "includePlatforms": [], + "includePlatforms": [ + "Editor" + ], "excludePlatforms": [], "allowUnsafeCode": false, "overrideReferences": false, diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials.meta b/Assets/UnitySensors/Runtime/Materials/CustomMaterials.meta new file mode 100644 index 00000000..20b990a9 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: d9d55a75b83b8f142970fe8edd34b140 +folderAsset: yes +DefaultImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat new file mode 100644 index 00000000..d2e43b31 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat @@ -0,0 +1,34 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!21 &2100000 +Material: + serializedVersion: 8 + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_Name: UnitySensors_DepthBufferLidar + m_Shader: {fileID: 4800000, guid: 9f39b9c496a4e9f489f510e6d57c5126, type: 3} + m_Parent: {fileID: 0} + m_ModifiedSerializedProperties: 0 + m_ValidKeywords: [] + m_InvalidKeywords: [] + m_LightmapFlags: 4 + m_EnableInstancingVariants: 0 + m_DoubleSidedGI: 0 + m_CustomRenderQueue: -1 + stringTagMap: {} + disabledShaderPasses: [] + m_LockedProperties: + m_SavedProperties: + serializedVersion: 3 + m_TexEnvs: [] + m_Ints: [] + m_Floats: + - _F: 150 + - _Y_COEF: 6 + - _Y_MAX: 1 + - _Y_MIN: 0.8333333 + m_Colors: [] + m_BuildTextureStacks: [] + m_AllowLocking: 1 diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat.meta b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat.meta new file mode 100644 index 00000000..f5347211 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_DepthBufferLidar.mat.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: 4d25d3a0a13f3d9489db78fe07061f16 +NativeFormatImporter: + externalObjects: {} + mainObjectFileID: 2100000 + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat new file mode 100644 index 00000000..74232ff8 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat @@ -0,0 +1,36 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!21 &2100000 +Material: + serializedVersion: 8 + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_Name: UnitySensors_PointCloudXYZ + m_Shader: {fileID: 4800000, guid: 0faabdfb36dc37944bd5237eb87dff3e, type: 3} + m_Parent: {fileID: 0} + m_ModifiedSerializedProperties: 0 + m_ValidKeywords: [] + m_InvalidKeywords: [] + m_LightmapFlags: 4 + m_EnableInstancingVariants: 0 + m_DoubleSidedGI: 0 + m_CustomRenderQueue: -1 + stringTagMap: {} + disabledShaderPasses: [] + m_LockedProperties: + m_SavedProperties: + serializedVersion: 3 + m_TexEnvs: + - _MainTex: + m_Texture: {fileID: 0} + m_Scale: {x: 1, y: 1} + m_Offset: {x: 0, y: 0} + m_Ints: [] + m_Floats: + - _Glossiness: 0.5 + - _Metallic: 0 + m_Colors: [] + m_BuildTextureStacks: [] + m_AllowLocking: 1 diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat.meta b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat.meta new file mode 100644 index 00000000..b2227582 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZ.mat.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: 7b5638bccb8c4de4b81e565745074a5d +NativeFormatImporter: + externalObjects: {} + mainObjectFileID: 2100000 + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat new file mode 100644 index 00000000..4f523492 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat @@ -0,0 +1,36 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!21 &2100000 +Material: + serializedVersion: 8 + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_Name: UnitySensors_PointCloudXYZI + m_Shader: {fileID: 4800000, guid: f9fa29512657a5b408ef0c50698b141b, type: 3} + m_Parent: {fileID: 0} + m_ModifiedSerializedProperties: 0 + m_ValidKeywords: [] + m_InvalidKeywords: [] + m_LightmapFlags: 4 + m_EnableInstancingVariants: 0 + m_DoubleSidedGI: 0 + m_CustomRenderQueue: -1 + stringTagMap: {} + disabledShaderPasses: [] + m_LockedProperties: + m_SavedProperties: + serializedVersion: 3 + m_TexEnvs: + - _MainTex: + m_Texture: {fileID: 0} + m_Scale: {x: 1, y: 1} + m_Offset: {x: 0, y: 0} + m_Ints: [] + m_Floats: + - _Glossiness: 0.5 + - _Metallic: 0 + m_Colors: [] + m_BuildTextureStacks: [] + m_AllowLocking: 1 diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat.meta b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat.meta new file mode 100644 index 00000000..ac1ec0ed --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZI.mat.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: ef4427209cbbb224f85dbf16125fc9b5 +NativeFormatImporter: + externalObjects: {} + mainObjectFileID: 2100000 + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat new file mode 100644 index 00000000..0994531c --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat @@ -0,0 +1,36 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!21 &2100000 +Material: + serializedVersion: 8 + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_Name: UnitySensors_PointCloudXYZRGB + m_Shader: {fileID: 4800000, guid: 417e6f59011b2b743a51b9344a78b15d, type: 3} + m_Parent: {fileID: 0} + m_ModifiedSerializedProperties: 0 + m_ValidKeywords: [] + m_InvalidKeywords: [] + m_LightmapFlags: 4 + m_EnableInstancingVariants: 0 + m_DoubleSidedGI: 0 + m_CustomRenderQueue: -1 + stringTagMap: {} + disabledShaderPasses: [] + m_LockedProperties: + m_SavedProperties: + serializedVersion: 3 + m_TexEnvs: + - _MainTex: + m_Texture: {fileID: 0} + m_Scale: {x: 1, y: 1} + m_Offset: {x: 0, y: 0} + m_Ints: [] + m_Floats: + - _Glossiness: 0.5 + - _Metallic: 0 + m_Colors: [] + m_BuildTextureStacks: [] + m_AllowLocking: 1 diff --git a/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat.meta b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat.meta new file mode 100644 index 00000000..378be318 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Materials/CustomMaterials/UnitySensors_PointCloudXYZRGB.mat.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: abdb03da013965d499191c3affaaa288 +NativeFormatImporter: + externalObjects: {} + mainObjectFileID: 2100000 + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab b/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab index 55dad53b..d6286b51 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab @@ -12,6 +12,7 @@ GameObject: - component: {fileID: 1105687583338018399} - component: {fileID: 1105687583338018398} - component: {fileID: 859923666563037401} + - component: {fileID: -1608031838711272521} m_Layer: 0 m_Name: DepthCamera m_TagString: Untagged @@ -26,13 +27,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1105687583338018395} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!20 &1105687583338018399 Camera: @@ -48,9 +49,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -95,6 +104,8 @@ MonoBehaviour: _minRange: 0.05 _maxRange: 100 _gaussianNoiseSigma: 0 + _depthCameraMat: {fileID: -876546973899608171, guid: a3c68fd340741ee4597690d59d7509a6, + type: 3} --- !u!114 &859923666563037401 MonoBehaviour: m_ObjectHideFlags: 0 @@ -108,3 +119,18 @@ MonoBehaviour: m_Name: m_EditorClassIdentifier: _source: {fileID: 1105687583338018398} +--- !u!114 &-1608031838711272521 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1105687583338018395} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 5202acb8ddfd0c546b69f23eb10b4e60, type: 3} + m_Name: + m_EditorClassIdentifier: + _source: {fileID: 1105687583338018398} + _sourceTexture: 0 + _image: {fileID: 0} diff --git a/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBCamera.prefab b/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBCamera.prefab index 2a34e64e..6ccc7fb7 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBCamera.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBCamera.prefab @@ -26,13 +26,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 6023160553514482222} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!20 &6023160553514482210 Camera: @@ -48,9 +48,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -92,8 +100,6 @@ MonoBehaviour: _frequency: 10 _resolution: {x: 640, y: 480} _fov: 30 - _minRange: 0.05 - _maxRange: 100 --- !u!114 &-4194670642642625912 MonoBehaviour: m_ObjectHideFlags: 0 diff --git a/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab b/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab index a28e1867..f16a1857 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab @@ -27,13 +27,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1785895639420286579} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!20 &1785895639420286583 Camera: @@ -49,9 +49,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -96,6 +104,8 @@ MonoBehaviour: _minRange: 0.05 _maxRange: 100 _gaussianNoiseSigma: 0 + _depthCameraMat: {fileID: -876546973899608171, guid: a3c68fd340741ee4597690d59d7509a6, + type: 3} --- !u!114 &4022873546115888586 MonoBehaviour: m_ObjectHideFlags: 0 diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab index 8873cde6..c3fb9a4d 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9219009776079660105} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.12065, z: 0} m_LocalScale: {x: 0.1655, y: 0.02065, z: 0.1655} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 9219009777779736545} - m_RootOrder: 2 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &9219009776079660106 MeshFilter: @@ -58,6 +58,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -108,13 +110,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9219009776518534072} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.06611, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 9219009777992118712} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &9219009776518534082 MonoBehaviour: @@ -137,6 +139,8 @@ MonoBehaviour: _maxIntensity: 255 _texturePixelsNum: 1500000 _textureSizePerCamera: {x: 0, y: 0} + _depthBufferLidarMat: {fileID: 2100000, guid: 4d25d3a0a13f3d9489db78fe07061f16, + type: 2} --- !u!114 &9107878023928292438 MonoBehaviour: m_ObjectHideFlags: 0 @@ -175,13 +179,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9219009777597040757} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.067, z: 0} m_LocalScale: {x: 0.1655, y: 0.0335, z: 0.1655} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 9219009777779736545} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &9219009777597040758 MeshFilter: @@ -208,6 +212,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -258,13 +264,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9219009777739667540} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0165, z: 0} m_LocalScale: {x: 0.1655, y: 0.0165, z: 0.1655} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 9219009777779736545} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &9219009777739667537 MeshFilter: @@ -291,6 +297,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -339,6 +347,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9219009777779736550} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -348,7 +357,6 @@ Transform: - {fileID: 9219009777597040756} - {fileID: 9219009776079660104} m_Father: {fileID: 9219009777992118712} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &9219009777992118713 GameObject: @@ -373,6 +381,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9219009777992118713} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -381,5 +390,4 @@ Transform: - {fileID: 9219009776518534085} - {fileID: 9219009777779736545} m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs index c75bb63b..53566bbf 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs @@ -23,13 +23,13 @@ public class DepthCameraSensor : CameraSensor, ITextureInterface, IPointCloudInt protected float _maxRange = 100.0f; [SerializeField] private float _gaussianNoiseSigma = 0.0f; + [SerializeField] + private Material _depthCameraMat; private UnityEngine.Camera _camera; private RenderTexture _rt = null; private Texture2D _texture; - private Material _mat; - private JobHandle _jobHandle; private IUpdateGaussianNoisesJob _updateGaussianNoisesJob; @@ -59,9 +59,6 @@ protected override void Init() _texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBAFloat, false); - _mat = new Material(Shader.Find("UnitySensors/Color2DepthCamera")); - float f = m_camera.farClipPlane; - SetupDirections(); SetupJob(); } @@ -154,7 +151,7 @@ protected override void OnSensorDestroy() private void OnRenderImage(RenderTexture source, RenderTexture dest) { - Graphics.Blit(null, dest, _mat); + Graphics.Blit(null, dest, _depthCameraMat); } } } diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/ITextureToColorPointsJob.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/ITextureToColorPointsJob.cs index 60d5c695..d0005a68 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/ITextureToColorPointsJob.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/ITextureToColorPointsJob.cs @@ -29,13 +29,14 @@ public struct ITextureToColorPointsJob : IJobParallelFor public void Execute(int index) { - float distance = (1.0f - Mathf.Clamp01(depthPixels.AsReadOnly()[index].r)) * far; + float distance = depthPixels.AsReadOnly()[index].r * far; float distance_noised = distance + noises[index]; distance = (near < distance && distance < far && near < distance_noised && distance_noised < far) ? distance_noised : 0; - + + float radius = distance / directions[index].z; PointXYZRGB point = new PointXYZRGB() { - position = directions[index] * distance, + position = directions[index] * radius, r = colorPixels[index].r, g = colorPixels[index].g, b = colorPixels[index].b, diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs index bcf026f2..a55665b7 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs @@ -23,6 +23,8 @@ public class RGBDCameraSensor : CameraSensor, ITextureInterface, IPointCloudInte protected float _maxRange = 100.0f; [SerializeField] private float _gaussianNoiseSigma = 0.0f; + [SerializeField] + private Material _depthCameraMat; private UnityEngine.Camera _depthCamera; private RenderTexture _depthRt = null; @@ -32,7 +34,6 @@ public class RGBDCameraSensor : CameraSensor, ITextureInterface, IPointCloudInte private RenderTexture _colorRt = null; private Texture2D _colorTexture; - private Material _mat; private JobHandle _jobHandle; @@ -74,9 +75,6 @@ protected override void Init() _depthTexture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBAFloat, false); _colorTexture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.BGRA32, false); - _mat = new Material(Shader.Find("UnitySensors/Color2Depth")); - float f = m_camera.farClipPlane; - _mat.SetFloat("_F", f); SetupDirections(); SetupJob(); @@ -143,7 +141,8 @@ protected override void UpdateSensor() private bool LoadDepthTexture() { bool result = false; - AsyncGPUReadback.Request(_depthRt, 0, request => { + AsyncGPUReadback.Request(_depthRt, 0, request => + { if (request.hasError) { } @@ -162,7 +161,8 @@ private bool LoadDepthTexture() private bool LoadColorTexture() { bool result = false; - AsyncGPUReadback.Request(_colorRt, 0, request => { + AsyncGPUReadback.Request(_colorRt, 0, request => + { if (request.hasError) { } @@ -190,7 +190,7 @@ protected override void OnSensorDestroy() private void OnRenderImage(RenderTexture source, RenderTexture dest) { - Graphics.Blit(source, dest, _mat); + Graphics.Blit(null, dest, _depthCameraMat); } } } diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs index 85e6cc77..440d4787 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs @@ -18,6 +18,7 @@ public class DepthBufferLiDARSensor : LiDARSensor private int _texturePixelsNum = 1; [SerializeField, Attribute.ReadOnly] private Vector2Int _textureSizePerCamera; + [SerializeField] Material _depthBufferLidarMat; private Transform _transform; @@ -48,7 +49,7 @@ private void SetupCamera() { float azimuthAngleRange = scanPattern.maxAzimuthAngle - scanPattern.minAzimuthAngle; _camerasNum = azimuthAngleRange > 0.0f ? Mathf.CeilToInt(azimuthAngleRange / 60.0f) : 1; - + _horizontalFOV = azimuthAngleRange / _camerasNum; float verticalFOV = Mathf.Max(1.0f, 2.0f * Mathf.Max(Mathf.Abs(scanPattern.maxZenithAngle), Mathf.Abs(scanPattern.minZenithAngle))); @@ -64,7 +65,7 @@ private void SetupCamera() { GameObject camera_obj = new GameObject(); camera_obj.name = "Camera " + i.ToString(); - + Transform camera_tf = camera_obj.transform; camera_tf.parent = _transform; camera_tf.localPosition = Vector3.zero; @@ -82,6 +83,7 @@ private void SetupCamera() camera.rect = rect; Color2Depth converter = camera_obj.AddComponent(); + converter.mat_source = _depthBufferLidarMat; converter.y_min = (float)i / _camerasNum; converter.y_max = (float)(i + 1.0f) / _camerasNum; converter.y_coef = _camerasNum; @@ -135,7 +137,7 @@ private void SetupJobs() indexOffset = 0, directions = _directions, pixelIndices = _pixelIndices, - noises =_noises, + noises = _noises, pixels = _pixels, points = pointCloud.points }; diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs index b495455f..93bfa98f 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs @@ -33,6 +33,7 @@ public struct ITextureToPointsJob : IJobParallelFor public void Execute(int index) { + // TODO: there is no need to invert the pixel color int pixelIndex = pixelIndices[index + indexOffset]; float distance = (1.0f - Mathf.Clamp01(pixels.AsReadOnly()[pixelIndex].r)) * far; float distance_noised = distance + noises[index]; @@ -42,7 +43,7 @@ public void Execute(int index) position = directions[index + indexOffset] * distance, intensity = (distance != 0) ? maxIntensity * sqrNear / (distance * distance) : 0 }; - + points[index] = point; } } diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs index ec541883..205541cf 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs @@ -24,6 +24,7 @@ public struct IUpdateRaycastCommandsJob : IJobParallelFor public void Execute(int index) { + // FIXME: Update the api raycastCommands[index] = new RaycastCommand(origin, localToWorldMatrix * (Vector3)directions[index + indexOffset], maxRange); } } diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/Camera/Color2Depth.cs b/Assets/UnitySensors/Runtime/Scripts/Utils/Camera/Color2Depth.cs index 782d16e9..d327f8a3 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Utils/Camera/Color2Depth.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Utils/Camera/Color2Depth.cs @@ -5,7 +5,8 @@ namespace UnitySensors.Utils.Camera [RequireComponent(typeof(UnityEngine.Camera))] public class Color2Depth : MonoBehaviour { - private Material _mat; + [System.NonSerialized] + public Material mat_source; [System.NonSerialized] public float y_min = 0.0f; @@ -13,10 +14,11 @@ public class Color2Depth : MonoBehaviour public float y_max = 1.0f; [System.NonSerialized] public float y_coef = 1.0f; + private Material _mat; private void Start() { - _mat = new Material(Shader.Find("UnitySensors/Color2Depth")); + _mat = new(mat_source); _mat.SetFloat("_F", GetComponent().farClipPlane); _mat.SetFloat("_Y_MIN", y_min); _mat.SetFloat("_Y_MAX", y_max); @@ -25,7 +27,7 @@ private void Start() private void OnRenderImage(RenderTexture source, RenderTexture dest) { - Graphics.Blit(source, dest, _mat); + Graphics.Blit(null, dest, _mat); } } } diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs index d2dee496..85248b83 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs @@ -6,6 +6,7 @@ namespace UnitySensors.Utils.PointCloud { + // TODO: Rewrite it with scriptable objects public static class PointUtilities { public readonly static ReadOnlyDictionary pointDataSizes = new ReadOnlyDictionary(new Dictionary @@ -17,6 +18,8 @@ public static class PointUtilities public readonly static ReadOnlyDictionary shaderNames = new ReadOnlyDictionary(new Dictionary { + // FIXME: Finding shaders by name need to add them to the "Always Included Shaders" list, or they will not work after building. + // Using the material reference would be better. { typeof(PointXYZ), "UnitySensors/PointCloudXYZ" }, { typeof(PointXYZI), "UnitySensors/PointCloudXYZI" }, { typeof(PointXYZRGB), "UnitySensors/PointCloudXYZRGB" } diff --git a/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader.meta b/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader.meta deleted file mode 100644 index 872d74f8..00000000 --- a/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader.meta +++ /dev/null @@ -1,10 +0,0 @@ -fileFormatVersion: 2 -guid: f4a211a4cf34db84a8d57a3e8d7a3413 -ShaderImporter: - externalObjects: {} - defaultTextures: [] - nonModifiableTextures: [] - preprocessorOverride: 0 - userData: - assetBundleName: - assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader b/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader deleted file mode 100644 index 2e691bf5..00000000 --- a/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader +++ /dev/null @@ -1,48 +0,0 @@ -Shader "UnitySensors/Color2DepthCamera" -{ - Properties - { - } - SubShader - { - Tags { "RenderType" = "Opaque" } - LOD 100 - - Pass - { - CGPROGRAM - #pragma vertex vert - #pragma fragment frag - #include "UnityCG.cginc" - - sampler2D _CameraDepthTexture; - - struct appdata - { - float4 vertex : POSITION; - float2 uv : TEXCOORD0; - }; - - struct v2f - { - float4 vertex : SV_POSITION; - float2 uv : TEXCOORD0; - }; - - v2f vert(appdata v) - { - v2f o; - o.vertex = UnityObjectToClipPos(v.vertex); - o.uv = v.uv; - return o; - } - - float4 frag(v2f i) : SV_Target - { - float depth01 = Linear01Depth(tex2D(_CameraDepthTexture, float2 (i.uv.x, i.uv.y )).r); - return float4(depth01, depth01, depth01, 1.0f); - } - ENDCG - } - } -} \ No newline at end of file diff --git a/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader b/Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader similarity index 90% rename from Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader rename to Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader index 39c63a8b..c62e0d8e 100644 --- a/Assets/UnitySensors/Runtime/Shaders/Color2Depth.shader +++ b/Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader @@ -1,5 +1,6 @@ -Shader "UnitySensors/Color2Depth" +Shader "UnitySensors/DepthBufferLidar" { + // TODO: rewrite it in shader graph to support URP/HDRP Properties { _F("_F", float) = 0.0 @@ -53,6 +54,8 @@ Shader "UnitySensors/Color2Depth" clip(_Y_MAX - i.uv.y); float depth01 = Linear01Depth(tex2D(_CameraDepthTexture, float2 (i.uv.x, (i.uv.y - _Y_MIN) * _Y_COEF)).r); float3 viewPos = (i.viewDir.xyz / i.viewDir.w) * depth01; + + // TODO: there is no need to invert the pixel color float distance = 1.0f - length(viewPos) / _F; return float4(distance, distance, distance, 1.0f); } diff --git a/Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader.meta b/Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader.meta similarity index 100% rename from Assets/UnitySensors/Runtime/Shaders/Color2DepthCamera.shader.meta rename to Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader.meta diff --git a/Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph b/Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph new file mode 100644 index 00000000..ce66e6ed --- /dev/null +++ b/Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph @@ -0,0 +1,377 @@ +{ + "m_SGVersion": 3, + "m_Type": "UnityEditor.ShaderGraph.GraphData", + "m_ObjectId": "f09bf3c0216e4b1787ba10e225acf952", + "m_Properties": [], + "m_Keywords": [], + "m_Dropdowns": [], + "m_CategoryData": [ + { + "m_Id": "8c00afd618a44d92870750b209399165" + } + ], + "m_Nodes": [ + { + "m_Id": "31e57edd921f4d4a8d7cc1be1d712478" + }, + { + "m_Id": "f9aa3de6e29f4ddaaeac6d81546d29fd" + }, + { + "m_Id": "4e98be9913a84bd7b190d26339d9e0ca" + }, + { + "m_Id": "4209c40c0f5b455a922e468e37931a7b" + } + ], + "m_GroupDatas": [], + "m_StickyNoteDatas": [], + "m_Edges": [ + { + "m_OutputSlot": { + "m_Node": { + "m_Id": "f9aa3de6e29f4ddaaeac6d81546d29fd" + }, + "m_SlotId": 1 + }, + "m_InputSlot": { + "m_Node": { + "m_Id": "31e57edd921f4d4a8d7cc1be1d712478" + }, + "m_SlotId": 0 + } + } + ], + "m_VertexContext": { + "m_Position": { + "x": 0.0, + "y": 0.0 + }, + "m_Blocks": [] + }, + "m_FragmentContext": { + "m_Position": { + "x": 0.0, + "y": 200.0 + }, + "m_Blocks": [ + { + "m_Id": "31e57edd921f4d4a8d7cc1be1d712478" + }, + { + "m_Id": "4e98be9913a84bd7b190d26339d9e0ca" + }, + { + "m_Id": "4209c40c0f5b455a922e468e37931a7b" + } + ] + }, + "m_PreviewData": { + "serializedMesh": { + "m_SerializedMesh": "{\"mesh\":{\"instanceID\":0}}", + "m_Guid": "" + }, + "preventRotation": false + }, + "m_Path": "Shader Graphs", + "m_GraphPrecision": 1, + "m_PreviewMode": 2, + "m_OutputNode": { + "m_Id": "" + }, + "m_ActiveTargets": [ + { + "m_Id": "176113b3c6f2433b84a4b8675dc81702" + } + ] +} + +{ + "m_SGVersion": 2, + "m_Type": "UnityEditor.Rendering.BuiltIn.ShaderGraph.BuiltInTarget", + "m_ObjectId": "176113b3c6f2433b84a4b8675dc81702", + "m_ActiveSubTarget": { + "m_Id": "76cc8e50845b4474abf7ffab9336e741" + }, + "m_AllowMaterialOverride": false, + "m_SurfaceType": 1, + "m_ZWriteControl": 0, + "m_ZTestMode": 4, + "m_AlphaMode": 0, + "m_RenderFace": 2, + "m_AlphaClip": false, + "m_CustomEditorGUI": "" +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.Vector1MaterialSlot", + "m_ObjectId": "1bd6b86fb4bd4b58824e414ad6e1524a", + "m_Id": 1, + "m_DisplayName": "Out", + "m_SlotType": 1, + "m_Hidden": false, + "m_ShaderOutputName": "Out", + "m_StageCapability": 2, + "m_Value": 0.0, + "m_DefaultValue": 0.0, + "m_Labels": [] +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.BlockNode", + "m_ObjectId": "31e57edd921f4d4a8d7cc1be1d712478", + "m_Group": { + "m_Id": "" + }, + "m_Name": "SurfaceDescription.BaseColor", + "m_DrawState": { + "m_Expanded": true, + "m_Position": { + "serializedVersion": "2", + "x": 0.0, + "y": 0.0, + "width": 0.0, + "height": 0.0 + } + }, + "m_Slots": [ + { + "m_Id": "5061dc8f70374bc29165edfef786263e" + } + ], + "synonyms": [], + "m_Precision": 0, + "m_PreviewExpanded": true, + "m_DismissedVersion": 0, + "m_PreviewMode": 0, + "m_CustomColors": { + "m_SerializableColors": [] + }, + "m_SerializedDescriptor": "SurfaceDescription.BaseColor" +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.BlockNode", + "m_ObjectId": "4209c40c0f5b455a922e468e37931a7b", + "m_Group": { + "m_Id": "" + }, + "m_Name": "SurfaceDescription.Emission", + "m_DrawState": { + "m_Expanded": true, + "m_Position": { + "serializedVersion": "2", + "x": 0.0, + "y": 0.0, + "width": 0.0, + "height": 0.0 + } + }, + "m_Slots": [ + { + "m_Id": "76d45648186a4dd3abd5bd4d1ad99090" + } + ], + "synonyms": [], + "m_Precision": 0, + "m_PreviewExpanded": true, + "m_DismissedVersion": 0, + "m_PreviewMode": 0, + "m_CustomColors": { + "m_SerializableColors": [] + }, + "m_SerializedDescriptor": "SurfaceDescription.Emission" +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.BlockNode", + "m_ObjectId": "4e98be9913a84bd7b190d26339d9e0ca", + "m_Group": { + "m_Id": "" + }, + "m_Name": "SurfaceDescription.Alpha", + "m_DrawState": { + "m_Expanded": true, + "m_Position": { + "serializedVersion": "2", + "x": 0.0, + "y": 0.0, + "width": 0.0, + "height": 0.0 + } + }, + "m_Slots": [ + { + "m_Id": "718a6b40e0994c4d9c80cc2bf639af92" + } + ], + "synonyms": [], + "m_Precision": 0, + "m_PreviewExpanded": true, + "m_DismissedVersion": 0, + "m_PreviewMode": 0, + "m_CustomColors": { + "m_SerializableColors": [] + }, + "m_SerializedDescriptor": "SurfaceDescription.Alpha" +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.ColorRGBMaterialSlot", + "m_ObjectId": "5061dc8f70374bc29165edfef786263e", + "m_Id": 0, + "m_DisplayName": "Base Color", + "m_SlotType": 0, + "m_Hidden": false, + "m_ShaderOutputName": "BaseColor", + "m_StageCapability": 2, + "m_Value": { + "x": 0.5, + "y": 0.5, + "z": 0.5 + }, + "m_DefaultValue": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + "m_Labels": [], + "m_ColorMode": 0, + "m_DefaultColor": { + "r": 0.5, + "g": 0.5, + "b": 0.5, + "a": 1.0 + } +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.ScreenPositionMaterialSlot", + "m_ObjectId": "645f357ed90d45a9afcda6907aac03b1", + "m_Id": 0, + "m_DisplayName": "UV", + "m_SlotType": 0, + "m_Hidden": false, + "m_ShaderOutputName": "UV", + "m_StageCapability": 3, + "m_Value": { + "x": 0.0, + "y": 0.0, + "z": 0.0, + "w": 0.0 + }, + "m_DefaultValue": { + "x": 0.0, + "y": 0.0, + "z": 0.0, + "w": 0.0 + }, + "m_Labels": [], + "m_ScreenSpaceType": 0 +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.Vector1MaterialSlot", + "m_ObjectId": "718a6b40e0994c4d9c80cc2bf639af92", + "m_Id": 0, + "m_DisplayName": "Alpha", + "m_SlotType": 0, + "m_Hidden": false, + "m_ShaderOutputName": "Alpha", + "m_StageCapability": 2, + "m_Value": 1.0, + "m_DefaultValue": 1.0, + "m_Labels": [] +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.Rendering.BuiltIn.ShaderGraph.BuiltInCanvasSubTarget", + "m_ObjectId": "76cc8e50845b4474abf7ffab9336e741" +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.ColorRGBMaterialSlot", + "m_ObjectId": "76d45648186a4dd3abd5bd4d1ad99090", + "m_Id": 0, + "m_DisplayName": "Emission", + "m_SlotType": 0, + "m_Hidden": false, + "m_ShaderOutputName": "Emission", + "m_StageCapability": 2, + "m_Value": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + "m_DefaultValue": { + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + "m_Labels": [], + "m_ColorMode": 1, + "m_DefaultColor": { + "r": 0.0, + "g": 0.0, + "b": 0.0, + "a": 1.0 + } +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.CategoryData", + "m_ObjectId": "8c00afd618a44d92870750b209399165", + "m_Name": "", + "m_ChildObjectList": [] +} + +{ + "m_SGVersion": 0, + "m_Type": "UnityEditor.ShaderGraph.SceneDepthNode", + "m_ObjectId": "f9aa3de6e29f4ddaaeac6d81546d29fd", + "m_Group": { + "m_Id": "" + }, + "m_Name": "Scene Depth", + "m_DrawState": { + "m_Expanded": true, + "m_Position": { + "serializedVersion": "2", + "x": -370.6666564941406, + "y": 200.00001525878907, + "width": 147.33334350585938, + "height": 114.66667175292969 + } + }, + "m_Slots": [ + { + "m_Id": "645f357ed90d45a9afcda6907aac03b1" + }, + { + "m_Id": "1bd6b86fb4bd4b58824e414ad6e1524a" + } + ], + "synonyms": [ + "zbuffer", + "zdepth" + ], + "m_Precision": 0, + "m_PreviewExpanded": true, + "m_DismissedVersion": 0, + "m_PreviewMode": 0, + "m_CustomColors": { + "m_SerializableColors": [] + }, + "m_DepthSamplingMode": 0 +} + diff --git a/Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph.meta b/Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph.meta new file mode 100644 index 00000000..4e757aa1 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Shaders/DepthCamera.shadergraph.meta @@ -0,0 +1,10 @@ +fileFormatVersion: 2 +guid: a3c68fd340741ee4597690d59d7509a6 +ScriptedImporter: + internalIDToNameTable: [] + externalObjects: {} + serializedVersion: 2 + userData: + assetBundleName: + assetBundleVariant: + script: {fileID: 11500000, guid: 625f186215c104763be7675aa2d941aa, type: 3} diff --git a/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZ.shader b/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZ.shader index 61f3ced9..23967dd6 100644 --- a/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZ.shader +++ b/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZ.shader @@ -1,5 +1,6 @@ Shader "UnitySensors/PointCloudXYZ" { + // TODO: rewrite it in shader graph to support URP/HDRP Properties{ _MainTex("Albedo (RGB)", 2D) = "white" {} _Glossiness("Smoothness", Range(0,1)) = 0.5 diff --git a/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZI.shader b/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZI.shader index 8f075129..46b090dd 100644 --- a/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZI.shader +++ b/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZI.shader @@ -1,5 +1,6 @@ Shader "UnitySensors/PointCloudXYZI" { + // TODO: rewrite it in shader graph to support URP/HDRP Properties{ _MainTex("Albedo (RGB)", 2D) = "white" {} _Glossiness("Smoothness", Range(0,1)) = 0.5 diff --git a/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZRGB.shader b/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZRGB.shader index 6545026a..1b2709ee 100644 --- a/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZRGB.shader +++ b/Assets/UnitySensors/Runtime/Shaders/PointCloudXYZRGB.shader @@ -1,5 +1,6 @@ Shader "UnitySensors/PointCloudXYZRGB" { + // TODO: rewrite it in shader graph to support URP/HDRP Properties{ _MainTex("Albedo (RGB)", 2D) = "white" {} _Glossiness("Smoothness", Range(0,1)) = 0.5 diff --git a/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity b/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity index e585ca98..86aebeb7 100644 --- a/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity +++ b/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity @@ -13,7 +13,7 @@ OcclusionCullingSettings: --- !u!104 &2 RenderSettings: m_ObjectHideFlags: 0 - serializedVersion: 9 + serializedVersion: 10 m_Fog: 0 m_FogColor: {r: 0.5, g: 0.5, b: 0.5, a: 1} m_FogMode: 3 @@ -38,13 +38,12 @@ RenderSettings: m_ReflectionIntensity: 1 m_CustomReflection: {fileID: 0} m_Sun: {fileID: 0} - m_IndirectSpecularColor: {r: 0.44657898, g: 0.4964133, b: 0.5748178, a: 1} + m_IndirectSpecularColor: {r: 0.18028378, g: 0.22571412, b: 0.30692285, a: 1} m_UseRadianceAmbientProbe: 0 --- !u!157 &3 LightmapSettings: m_ObjectHideFlags: 0 serializedVersion: 12 - m_GIWorkflowMode: 1 m_GISettings: serializedVersion: 2 m_BounceScale: 1 @@ -67,9 +66,6 @@ LightmapSettings: m_LightmapParameters: {fileID: 0} m_LightmapsBakeMode: 1 m_TextureCompression: 1 - m_FinalGather: 0 - m_FinalGatherFiltering: 1 - m_FinalGatherRayCount: 256 m_ReflectionCompression: 2 m_MixedBakeMode: 2 m_BakeBackend: 1 @@ -97,14 +93,14 @@ LightmapSettings: m_ExportTrainingData: 0 m_TrainingDataDestination: TrainingData m_LightProbeSampleCountMultiplier: 4 - m_LightingDataAsset: {fileID: 0} + m_LightingDataAsset: {fileID: 20201, guid: 0000000000000000f000000000000000, type: 0} m_LightingSettings: {fileID: 0} --- !u!196 &4 NavMeshSettings: serializedVersion: 2 m_ObjectHideFlags: 0 m_BuildSettings: - serializedVersion: 2 + serializedVersion: 3 agentTypeID: 0 agentRadius: 0.5 agentHeight: 2 @@ -117,7 +113,7 @@ NavMeshSettings: cellSize: 0.16666667 manualTileSize: 0 tileSize: 256 - accuratePlacement: 0 + buildHeightMesh: 0 maxJobWorkers: 0 preserveTilesOutsideBounds: 0 debug: @@ -189,7 +185,6 @@ RectTransform: m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 445338817} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} m_AnchorMin: {x: 0.5, y: 0.5} m_AnchorMax: {x: 0.5, y: 0.5} @@ -221,9 +216,8 @@ Light: m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 407419871} m_Enabled: 1 - serializedVersion: 10 + serializedVersion: 11 m_Type: 1 - m_Shape: 0 m_Color: {r: 1, g: 0.95686275, b: 0.8392157, a: 1} m_Intensity: 1 m_Range: 10 @@ -282,13 +276,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 407419871} + serializedVersion: 2 m_LocalRotation: {x: 0.40821788, y: -0.23456968, z: 0.10938163, w: 0.8754261} m_LocalPosition: {x: 0, y: 3, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 50, y: -30, z: 0} --- !u!1 &445338813 GameObject: @@ -338,12 +332,12 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: 0cd44c1031e13a943bb63640046fad76, type: 3} m_Name: m_EditorClassIdentifier: - m_UiScaleMode: 0 + m_UiScaleMode: 1 m_ReferencePixelsPerUnit: 100 m_ScaleFactor: 1 - m_ReferenceResolution: {x: 800, y: 600} + m_ReferenceResolution: {x: 1920, y: 1080} m_ScreenMatchMode: 0 - m_MatchWidthOrHeight: 0 + m_MatchWidthOrHeight: 1 m_PhysicalUnit: 3 m_FallbackScreenDPI: 96 m_DefaultSpriteDPI: 96 @@ -366,7 +360,9 @@ Canvas: m_OverrideSorting: 0 m_OverridePixelPerfect: 0 m_SortingBucketNormalizedSize: 0 + m_VertexColorAlwaysGammaSpace: 0 m_AdditionalShaderChannelsFlag: 0 + m_UpdateRectTransformForStandalone: 0 m_SortingLayerID: 0 m_SortingOrder: 0 m_TargetDisplay: 0 @@ -385,7 +381,6 @@ RectTransform: - {fileID: 1896987095} - {fileID: 169596267} m_Father: {fileID: 0} - m_RootOrder: 2 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} m_AnchorMin: {x: 0, y: 0} m_AnchorMax: {x: 0, y: 0} @@ -458,19 +453,20 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1437038471} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 3 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1001 &1800507287 PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 0} m_Modifications: - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, @@ -534,6 +530,17 @@ PrefabInstance: value: DemoEnv objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 6023160555534991738} + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 1105687582532461537} + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: 581b84ef57339314c92df1cef0a06b47, type: 3} --- !u!1 &1896987094 GameObject: @@ -566,7 +573,6 @@ RectTransform: m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 445338817} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} m_AnchorMin: {x: 0.5, y: 0.5} m_AnchorMax: {x: 0.5, y: 0.5} @@ -648,9 +654,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -684,21 +698,27 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 2021466618} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 100, y: 1, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 4 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1001 &1105687582532461536 PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 952137284} m_Modifications: + - target: {fileID: -1608031838711272521, guid: 20f112f7f4e74c84693eb6c82e49358f, + type: 3} + propertyPath: _image + value: + objectReference: {fileID: 169596265} - target: {fileID: 1105687583338018336, guid: 20f112f7f4e74c84693eb6c82e49358f, type: 3} propertyPath: m_RootOrder @@ -780,14 +800,29 @@ PrefabInstance: value: 0.1 objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: [] + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: 20f112f7f4e74c84693eb6c82e49358f, type: 3} +--- !u!4 &1105687582532461537 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 1105687583338018336, guid: 20f112f7f4e74c84693eb6c82e49358f, + type: 3} + m_PrefabInstance: {fileID: 1105687582532461536} + m_PrefabAsset: {fileID: 0} --- !u!1001 &6023160555534991737 PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 952137284} m_Modifications: + - target: {fileID: -4194670642642625912, guid: c2bfd499605c88945b93d09de59d15df, + type: 3} + propertyPath: _image + value: + objectReference: {fileID: 1896987096} - target: {fileID: 6023160553514482209, guid: c2bfd499605c88945b93d09de59d15df, type: 3} propertyPath: m_RootOrder @@ -854,4 +889,22 @@ PrefabInstance: value: RGBCamera objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: [] + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: c2bfd499605c88945b93d09de59d15df, type: 3} +--- !u!4 &6023160555534991738 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 6023160553514482209, guid: c2bfd499605c88945b93d09de59d15df, + type: 3} + m_PrefabInstance: {fileID: 6023160555534991737} + m_PrefabAsset: {fileID: 0} +--- !u!1660057539 &9223372036854775807 +SceneRoots: + m_ObjectHideFlags: 0 + m_Roots: + - {fileID: 407419873} + - {fileID: 1800507287} + - {fileID: 445338817} + - {fileID: 1437038474} + - {fileID: 2021466621} diff --git a/Assets/UnitySensors/Samples/Camera/Demo_RGBCamera.unity b/Assets/UnitySensors/Samples/Camera/Demo_RGBCamera.unity index 28d73b5f..3eaf1d98 100644 --- a/Assets/UnitySensors/Samples/Camera/Demo_RGBCamera.unity +++ b/Assets/UnitySensors/Samples/Camera/Demo_RGBCamera.unity @@ -13,7 +13,7 @@ OcclusionCullingSettings: --- !u!104 &2 RenderSettings: m_ObjectHideFlags: 0 - serializedVersion: 9 + serializedVersion: 10 m_Fog: 0 m_FogColor: {r: 0.5, g: 0.5, b: 0.5, a: 1} m_FogMode: 3 @@ -38,13 +38,12 @@ RenderSettings: m_ReflectionIntensity: 1 m_CustomReflection: {fileID: 0} m_Sun: {fileID: 0} - m_IndirectSpecularColor: {r: 0.44657898, g: 0.4964133, b: 0.5748178, a: 1} + m_IndirectSpecularColor: {r: 0.18028378, g: 0.22571412, b: 0.30692285, a: 1} m_UseRadianceAmbientProbe: 0 --- !u!157 &3 LightmapSettings: m_ObjectHideFlags: 0 serializedVersion: 12 - m_GIWorkflowMode: 1 m_GISettings: serializedVersion: 2 m_BounceScale: 1 @@ -67,9 +66,6 @@ LightmapSettings: m_LightmapParameters: {fileID: 0} m_LightmapsBakeMode: 1 m_TextureCompression: 1 - m_FinalGather: 0 - m_FinalGatherFiltering: 1 - m_FinalGatherRayCount: 256 m_ReflectionCompression: 2 m_MixedBakeMode: 2 m_BakeBackend: 1 @@ -97,14 +93,14 @@ LightmapSettings: m_ExportTrainingData: 0 m_TrainingDataDestination: TrainingData m_LightProbeSampleCountMultiplier: 4 - m_LightingDataAsset: {fileID: 0} + m_LightingDataAsset: {fileID: 20201, guid: 0000000000000000f000000000000000, type: 0} m_LightingSettings: {fileID: 0} --- !u!196 &4 NavMeshSettings: serializedVersion: 2 m_ObjectHideFlags: 0 m_BuildSettings: - serializedVersion: 2 + serializedVersion: 3 agentTypeID: 0 agentRadius: 0.5 agentHeight: 2 @@ -117,7 +113,7 @@ NavMeshSettings: cellSize: 0.16666667 manualTileSize: 0 tileSize: 256 - accuratePlacement: 0 + buildHeightMesh: 0 maxJobWorkers: 0 preserveTilesOutsideBounds: 0 debug: @@ -163,9 +159,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -199,13 +203,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 62720512} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 100, y: 1, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 4 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &135884633 GameObject: @@ -232,9 +236,8 @@ Light: m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 135884633} m_Enabled: 1 - serializedVersion: 10 + serializedVersion: 11 m_Type: 1 - m_Shape: 0 m_Color: {r: 1, g: 0.95686275, b: 0.8392157, a: 1} m_Intensity: 1 m_Range: 10 @@ -293,19 +296,20 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 135884633} + serializedVersion: 2 m_LocalRotation: {x: 0.40821788, y: -0.23456968, z: 0.10938163, w: 0.8754261} m_LocalPosition: {x: 0, y: 3, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 50, y: -30, z: 0} --- !u!1001 &189404109 PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 0} m_Modifications: - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, @@ -369,6 +373,13 @@ PrefabInstance: value: DemoEnv objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 512758586} + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: 581b84ef57339314c92df1cef0a06b47, type: 3} --- !u!1 &492062520 GameObject: @@ -401,7 +412,6 @@ RectTransform: m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 1180426313} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} m_AnchorMin: {x: 0.5, y: 0.5} m_AnchorMax: {x: 0.5, y: 0.5} @@ -448,8 +458,14 @@ PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 1454009686} m_Modifications: + - target: {fileID: -4194670642642625912, guid: c2bfd499605c88945b93d09de59d15df, + type: 3} + propertyPath: _image + value: + objectReference: {fileID: 492062522} - target: {fileID: 6023160553514482209, guid: c2bfd499605c88945b93d09de59d15df, type: 3} propertyPath: m_RootOrder @@ -526,7 +542,16 @@ PrefabInstance: value: RGBCamera objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: [] + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: c2bfd499605c88945b93d09de59d15df, type: 3} +--- !u!4 &512758586 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 6023160553514482209, guid: c2bfd499605c88945b93d09de59d15df, + type: 3} + m_PrefabInstance: {fileID: 512758585} + m_PrefabAsset: {fileID: 0} --- !u!1 &1180426309 GameObject: m_ObjectHideFlags: 0 @@ -575,12 +600,12 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: 0cd44c1031e13a943bb63640046fad76, type: 3} m_Name: m_EditorClassIdentifier: - m_UiScaleMode: 0 + m_UiScaleMode: 1 m_ReferencePixelsPerUnit: 100 m_ScaleFactor: 1 - m_ReferenceResolution: {x: 800, y: 600} + m_ReferenceResolution: {x: 1920, y: 1080} m_ScreenMatchMode: 0 - m_MatchWidthOrHeight: 0 + m_MatchWidthOrHeight: 1 m_PhysicalUnit: 3 m_FallbackScreenDPI: 96 m_DefaultSpriteDPI: 96 @@ -603,7 +628,9 @@ Canvas: m_OverrideSorting: 0 m_OverridePixelPerfect: 0 m_SortingBucketNormalizedSize: 0 + m_VertexColorAlwaysGammaSpace: 0 m_AdditionalShaderChannelsFlag: 0 + m_UpdateRectTransformForStandalone: 0 m_SortingLayerID: 0 m_SortingOrder: 0 m_TargetDisplay: 0 @@ -621,7 +648,6 @@ RectTransform: m_Children: - {fileID: 492062521} m_Father: {fileID: 0} - m_RootOrder: 2 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} m_AnchorMin: {x: 0, y: 0} m_AnchorMax: {x: 0, y: 0} @@ -694,11 +720,20 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1489775038} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 3 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1660057539 &9223372036854775807 +SceneRoots: + m_ObjectHideFlags: 0 + m_Roots: + - {fileID: 135884635} + - {fileID: 189404109} + - {fileID: 1180426313} + - {fileID: 1489775041} + - {fileID: 62720515} diff --git a/Assets/UnitySensorsROS/Editor/UnitySensorsROSEditor.asmdef b/Assets/UnitySensorsROS/Editor/UnitySensorsROSEditor.asmdef index 7d9186d6..5a031a29 100644 --- a/Assets/UnitySensorsROS/Editor/UnitySensorsROSEditor.asmdef +++ b/Assets/UnitySensorsROS/Editor/UnitySensorsROSEditor.asmdef @@ -4,7 +4,9 @@ "references": [ "GUID:fa38f881a10f6314fa784b8975c16eff" ], - "includePlatforms": [], + "includePlatforms": [ + "Editor" + ], "excludePlatforms": [], "allowUnsafeCode": false, "overrideReferences": false, diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab index 7c6942af..9614825c 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab @@ -28,13 +28,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4853532333615571027} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!20 &4853532333615571031 Camera: @@ -50,9 +50,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -97,6 +105,8 @@ MonoBehaviour: _minRange: 0.05 _maxRange: 20 _gaussianNoiseSigma: 0 + _depthCameraMat: {fileID: -876546973899608171, guid: a3c68fd340741ee4597690d59d7509a6, + type: 3} --- !u!114 &4853532333615570985 MonoBehaviour: m_ObjectHideFlags: 0 diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab index fac2ba6a..e73bf367 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab @@ -27,13 +27,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 2016422477619200586} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!20 &2016422477619200582 Camera: @@ -49,9 +49,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -93,8 +101,6 @@ MonoBehaviour: _frequency: 10 _resolution: {x: 640, y: 480} _fov: 30 - _minRange: 0.05 - _maxRange: 100 --- !u!114 &2016422477619200579 MonoBehaviour: m_ObjectHideFlags: 0 diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab index 292f10b0..71092d82 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab @@ -29,13 +29,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4414791596585746458} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!20 &4414791596585746462 Camera: @@ -51,9 +51,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -98,6 +106,8 @@ MonoBehaviour: _minRange: 0.05 _maxRange: 100 _gaussianNoiseSigma: 0 + _depthCameraMat: {fileID: -876546973899608171, guid: a3c68fd340741ee4597690d59d7509a6, + type: 3} --- !u!114 &4414791596585746528 MonoBehaviour: m_ObjectHideFlags: 0 @@ -110,11 +120,12 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: ca85518969b9bf94aa9948188d795075, type: 3} m_Name: m_EditorClassIdentifier: - _source: {fileID: 6928715047789551323} _frequency: 10 _topicName: /camera/info _serializer: + _source: {fileID: 0} _header: + _source: {fileID: 0} _frame_id: /camera_frame --- !u!114 &2224187045829796718 MonoBehaviour: @@ -128,12 +139,13 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: 24143da40ec715f40bf587d63ce67ed2, type: 3} m_Name: m_EditorClassIdentifier: - _source: {fileID: 6928715047789551323} _frequency: 10 _topicName: /camera/depth/points _serializer: _header: + _source: {fileID: 0} _frame_id: /camera_frame + _source: {fileID: 6928715047789551323} --- !u!114 &6110166055807567966 MonoBehaviour: m_ObjectHideFlags: 0 @@ -146,12 +158,13 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: b474a6242e811f04488e3cb67b65dd35, type: 3} m_Name: m_EditorClassIdentifier: - _source: {fileID: 6928715047789551323} _frequency: 10 _topicName: /camera/depth/image/compressed _serializer: + _source: {fileID: 0} _sourceTexture: 0 _header: + _source: {fileID: 0} _frame_id: /camera_frame quality: 75 --- !u!114 &8736958369943202624 @@ -166,11 +179,12 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: b474a6242e811f04488e3cb67b65dd35, type: 3} m_Name: m_EditorClassIdentifier: - _source: {fileID: 6928715047789551323} _frequency: 10 _topicName: /camera/color/image/compressed _serializer: + _source: {fileID: 0} _sourceTexture: 1 _header: + _source: {fileID: 0} _frame_id: /camera_frame quality: 75 diff --git a/ProjectSettings/EditorBuildSettings.asset b/ProjectSettings/EditorBuildSettings.asset index 50d6f498..2742e61b 100644 --- a/ProjectSettings/EditorBuildSettings.asset +++ b/ProjectSettings/EditorBuildSettings.asset @@ -5,9 +5,13 @@ EditorBuildSettings: m_ObjectHideFlags: 0 serializedVersion: 2 m_Scenes: - - enabled: 1 + - enabled: 0 path: Assets/UnitySensors/Samples/TF/TF.unity guid: e84e2ab71efe63b4a984b45a10c6ff38 + - enabled: 1 + path: Assets/Tests/Scenes/Demo_Depth.unity + guid: cbce8c5c5c7011d4b951431b0b177324 m_configObjects: com.unity.addressableassets: {fileID: 11400000, guid: 18f8076c387088155a4fefb632dbebe6, type: 2} + m_UseUCBPForAssetBundles: 0 diff --git a/ProjectSettings/GraphicsSettings.asset b/ProjectSettings/GraphicsSettings.asset index 43369e3c..e1275984 100644 --- a/ProjectSettings/GraphicsSettings.asset +++ b/ProjectSettings/GraphicsSettings.asset @@ -3,7 +3,7 @@ --- !u!30 &1 GraphicsSettings: m_ObjectHideFlags: 0 - serializedVersion: 13 + serializedVersion: 16 m_Deferred: m_Mode: 1 m_Shader: {fileID: 69, guid: 0000000000000000f000000000000000, type: 0} @@ -13,9 +13,6 @@ GraphicsSettings: m_ScreenSpaceShadows: m_Mode: 1 m_Shader: {fileID: 64, guid: 0000000000000000f000000000000000, type: 0} - m_LegacyDeferred: - m_Mode: 1 - m_Shader: {fileID: 63, guid: 0000000000000000f000000000000000, type: 0} m_DepthNormals: m_Mode: 1 m_Shader: {fileID: 62, guid: 0000000000000000f000000000000000, type: 0} @@ -28,6 +25,7 @@ GraphicsSettings: m_LensFlare: m_Mode: 1 m_Shader: {fileID: 102, guid: 0000000000000000f000000000000000, type: 0} + m_VideoShadersIncludeMode: 2 m_AlwaysIncludedShaders: - {fileID: 7, guid: 0000000000000000f000000000000000, type: 0} - {fileID: 15104, guid: 0000000000000000f000000000000000, type: 0} @@ -35,7 +33,11 @@ GraphicsSettings: - {fileID: 15106, guid: 0000000000000000f000000000000000, type: 0} - {fileID: 10753, guid: 0000000000000000f000000000000000, type: 0} - {fileID: 10770, guid: 0000000000000000f000000000000000, type: 0} + - {fileID: 4800000, guid: 0faabdfb36dc37944bd5237eb87dff3e, type: 3} + - {fileID: 4800000, guid: f9fa29512657a5b408ef0c50698b141b, type: 3} + - {fileID: 4800000, guid: 417e6f59011b2b743a51b9344a78b15d, type: 3} m_PreloadedShaders: [] + m_PreloadShadersBatchTimeLimit: -1 m_SpritesDefaultMaterial: {fileID: 10754, guid: 0000000000000000f000000000000000, type: 0} m_CustomRenderPipeline: {fileID: 0} @@ -47,6 +49,7 @@ GraphicsSettings: m_LightmapStripping: 0 m_FogStripping: 0 m_InstancingStripping: 0 + m_BrgStripping: 0 m_LightmapKeepPlain: 1 m_LightmapKeepDirCombined: 1 m_LightmapKeepDynamicPlain: 1 @@ -57,7 +60,11 @@ GraphicsSettings: m_FogKeepExp: 1 m_FogKeepExp2: 1 m_AlbedoSwatchInfos: [] + m_RenderPipelineGlobalSettingsMap: {} m_LightsUseLinearIntensity: 0 m_LightsUseColorTemperature: 0 + m_DefaultRenderingLayerMask: 1 m_LogWhenShaderIsCompiled: 0 - m_AllowEnlightenSupportForUpgradedProject: 0 + m_LightProbeOutsideHullStrategy: 0 + m_CameraRelativeLightCulling: 0 + m_CameraRelativeShadowCulling: 0 From e4f1c15e5678e6f7b74b3dff35fa5e74b50f4ee9 Mon Sep 17 00:00:00 2001 From: chy <1274653465@qq.com> Date: Sun, 17 Nov 2024 20:27:38 +0800 Subject: [PATCH 06/15] Add documents and related images migrated to URP/HDRP --- .image/HDRP_ShaderGraph.png | 3 ++ .image/HDRP_convert_materials.png | 3 ++ .image/HDRP_custom_pass.png | 3 ++ .image/HDRP_final_result.png | 3 ++ .image/URP_ShaderGraph.png | 3 ++ .image/URP_camera_renderer.png | 3 ++ .image/URP_convert_materials.png | 3 ++ .image/URP_final_result.png | 3 ++ .image/URP_post_process.png | 3 ++ .image/URP_render_list.png | 3 ++ MigrateToURP&HDRP.md | 71 +++++++++++++++++++++++++++++++ README.md | 7 +++ 12 files changed, 108 insertions(+) create mode 100644 .image/HDRP_ShaderGraph.png create mode 100644 .image/HDRP_convert_materials.png create mode 100644 .image/HDRP_custom_pass.png create mode 100644 .image/HDRP_final_result.png create mode 100644 .image/URP_ShaderGraph.png create mode 100644 .image/URP_camera_renderer.png create mode 100644 .image/URP_convert_materials.png create mode 100644 .image/URP_final_result.png create mode 100644 .image/URP_post_process.png create mode 100644 .image/URP_render_list.png create mode 100644 MigrateToURP&HDRP.md diff --git a/.image/HDRP_ShaderGraph.png b/.image/HDRP_ShaderGraph.png new file mode 100644 index 00000000..956d0037 --- /dev/null +++ b/.image/HDRP_ShaderGraph.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:32462607540b93d20f2c5a5fcf8bd064c6f11ed999d121f8458bac589cbf6581 +size 55046 diff --git a/.image/HDRP_convert_materials.png b/.image/HDRP_convert_materials.png new file mode 100644 index 00000000..53c11f86 --- /dev/null +++ b/.image/HDRP_convert_materials.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d64e265f5ba6b33c0292ead28ddf98d90880130da5290b94e71be4c18d6d37fa +size 167542 diff --git a/.image/HDRP_custom_pass.png b/.image/HDRP_custom_pass.png new file mode 100644 index 00000000..bb0d1244 --- /dev/null +++ b/.image/HDRP_custom_pass.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a1cacc5e0fd701c91a4913d07a94018c35aa11e517ab353627b706a7e6678a4c +size 229802 diff --git a/.image/HDRP_final_result.png b/.image/HDRP_final_result.png new file mode 100644 index 00000000..61f279b5 --- /dev/null +++ b/.image/HDRP_final_result.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:90b53e42024b869ed72b5cb942804428823a33b18f6daa982104518dd79e0c3b +size 794561 diff --git a/.image/URP_ShaderGraph.png b/.image/URP_ShaderGraph.png new file mode 100644 index 00000000..e08197db --- /dev/null +++ b/.image/URP_ShaderGraph.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:258d9d7a61a4a52b3433ca4bd9ffd50c42f6a8039816e2d8d930cc8db95020b6 +size 37397 diff --git a/.image/URP_camera_renderer.png b/.image/URP_camera_renderer.png new file mode 100644 index 00000000..2a879ae1 --- /dev/null +++ b/.image/URP_camera_renderer.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a0afc664910b9e695eff77dd15cb96cbb18c3664f98611f0cec8504a3c0dd832 +size 90905 diff --git a/.image/URP_convert_materials.png b/.image/URP_convert_materials.png new file mode 100644 index 00000000..7bc5fb2b --- /dev/null +++ b/.image/URP_convert_materials.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:94d9d1232e35377609b2392a4bc44caa7ee8046c899752a642fc67b5b7de66a5 +size 108828 diff --git a/.image/URP_final_result.png b/.image/URP_final_result.png new file mode 100644 index 00000000..a4b4dd44 --- /dev/null +++ b/.image/URP_final_result.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:daccd786fd1a8e6e2a1318b6c3875f1aff1f5d0780247ce4759305dbc62df8fc +size 599623 diff --git a/.image/URP_post_process.png b/.image/URP_post_process.png new file mode 100644 index 00000000..1ec6a46b --- /dev/null +++ b/.image/URP_post_process.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cca8c37d29d7f81473cb7ab2ad6ab3101fae0243edef0002e21c12d260154545 +size 299344 diff --git a/.image/URP_render_list.png b/.image/URP_render_list.png new file mode 100644 index 00000000..ab841934 --- /dev/null +++ b/.image/URP_render_list.png @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:09a9584e861e323ed3cb406b6e00f4bb1a75c9865163b448d509d0ba9c7262bc +size 47218 diff --git a/MigrateToURP&HDRP.md b/MigrateToURP&HDRP.md new file mode 100644 index 00000000..5eabf63e --- /dev/null +++ b/MigrateToURP&HDRP.md @@ -0,0 +1,71 @@ +# Migrating To URP/HDRP +Only the sensors or visualizers written with **custom shaders** need to be migrated to URP/HDRP. The rest of them will work without any changes. + +Which means the **Depth Camera**, **RGBD Camera**, **DepthBuffer Lidar** and the **Point Cloud Visualizers** need to be migrated. + +In addition to the shader, the post-processing steps are also different in URP/HDRP. In the built-in pipeline, the post-processing is applied in the `OnRenderImage` method of the script. In URP/HDRP, the post-processing steps are different. + +> \[!NOTE] +> +> Now only support migrating the **Depth Camera** and **RGBD Camera** to URP/HDRP. + +## Migrating to URP + +1. Create the URP project + +2. Install the [ROS-TCP-Connector](https://github.com/Unity-Technologies/ROS-TCP-Connector) package + +3. Copy the `UnitySensors` and `UnitySensorsROS` folders to the project + +4. Update the materials from `Window` -> `Rendering` -> `Render Pipeline Converter`. Tick the `Rendering Settings` and `Material Upgrade` then click `Initialize And Convert` + + + +5. Open `DepthCamera` Shader Graph, change `Active Targets` from `Built-in` to `Univsrsal`, then change the material to `Fullscreen` and click `Save Asset` + + ![](.image/URP_ShaderGraph.png) + +6. Go to the `Settings` folder, create a new `URP Universal Render` asset called `URP-DepthCamera-Renderer`, and add the `Full Screen Pass Renderer Feture` on it + +7. On the `Full Screen Pass Renderer Feture`, select the `DepthCamera` Shader Graph as the `Pass Material`. + + ![](.image/URP_post_process.png) + +8. Add the `URP-DepthCamera-Renderer` to the `Renderer List` of `Default Render Pipeline Asset`, such as the `URP-HighFidelity` asset. And tick the `Depth Texture` selection + + ![](.image/URP_render_list.png) + +9. Select the `DepthCamera` and `RGBDCamera` prefabs, set their renderer to `URP-DepthCamera-Renderer` + + ![](.image/URP_camera_renderer.png) + +10. The **Depth Camera** and **RGBD Camera** should work normally in URP + + ![](.image/URP_final_result.png) + + +## Migrating to HDRP + +Migrating to HDRP is relatively simple. You need to: + +1. Create the HDRP project + +2. Install the [ROS-TCP-Connector](https://github.com/Unity-Technologies/ROS-TCP-Connector) package + +3. Copy the `UnitySensors` and `UnitySensorsROS` folders to the project + +4. Update the materials from `Window` -> `Rendering` -> `HDRP Wizard`. Click `Convert All Built-in Materials to HDRP` + + ![](.image/HDRP_convert_materials.png) + +5. Open `DepthCamera` Shader Graph, change `Active Targets` from `Built-in` to `HDRP`, then change the material to `Fullscreen` and click `Save Asset` + + ![](.image/HDRP_ShaderGraph.png) + +6. Add a custom pass volume in the scene via `Volume` -> `Custom Pass`. Set the `Mode`to `Camera`, drag the **Depth Camera** or **RGBD Camera** in the scene to the `Target Camera`. Add the `Full Screen Custom Pass` in the `Custom Passes` list. Set the `FullScreen Material` to `DepthCamera` Shader Graph. + + ![](.image/HDRP_custom_pass.png) + +7. The **Depth Camera** and **RGBD Camera** should work normally in HDRP + + ![](.image/HDRP_final_result.png) \ No newline at end of file diff --git a/README.md b/README.md index d7d2cd23..42f11559 100644 --- a/README.md +++ b/README.md @@ -62,6 +62,10 @@ To receive the data in ROS take a look at [ROS-TCP-Endpoint][external-RosTCPEndp 2. Build your workspace. 3. Launch ROS endpoint node. +### Migrating to URP/HDRP + +Please refer to [Migrating to URP/HDRP](MigrateToURP&HDRP.md). + ## 🤠Contributing
@@ -109,3 +113,6 @@ Unless required by applicable law or agreed to in writing, software distributed [github-release-link]: https://github.com/Field-Robotics-Japan/UnitySensors/releases [github-release-shield]: https://img.shields.io/github/v/release/Field-Robotics-Japan/UnitySensors?color=9BF6FF&logo=github&style=flat-square + + +[MigrateToURP&HDRP.md]: From ba453715912040354919b21a56c65127d106ea66 Mon Sep 17 00:00:00 2001 From: chy <1274653465@qq.com> Date: Sun, 17 Nov 2024 20:31:13 +0800 Subject: [PATCH 07/15] TODO: fix depth publish in ROS --- .../Serializers/SensorMsgs/CompressedImageMsgSerializer.cs | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs index 11dc8844..65777f33 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs @@ -35,6 +35,9 @@ public override void Init() _header.Init(); _sourceInterface = _source as ITextureInterface; _msg.format = "jpeg"; + // FIXME: Depth image should not be compressed as jpeg. + // It is normally encoded as 32FC1 and 16UC1, whose units are meters and millimeters respectively. + // So we need a new serializer for depth images. } public override CompressedImageMsg Serialize() From 37205d628ea03cc0229138549355e3b1e7fa2409 Mon Sep 17 00:00:00 2001 From: DESKTOP-E4VIK7O <1274653465@qq.com> Date: Mon, 18 Nov 2024 17:35:36 +0800 Subject: [PATCH 08/15] Added Unity scenes for Demo_RGBDCamera and Demo_RGBDCamera_ros; fixed null references in RGBDCamera_ros prefab; adjusted texture format in RGBCameraSensor; updated ImageMsgSerializer to support raw texture data serialization . --- .../Camera/RGBCamera/RGBCameraSensor.cs | 7 +- .../Samples/Camera/Demo_RGBDCamera.unity | 714 ++++++++++++++++++ .../Samples/Camera/Demo_RGBDCamera.unity.meta | 7 + .../Prefabs/Camera/RGBDCamera_ros.prefab | 16 +- .../SensorMsgs/ImageMsgSerializer.cs | 13 +- .../Samples/Camera/Demo_RGBDCamera_ros.unity | 473 ++++++++++++ .../Camera/Demo_RGBDCamera_ros.unity.meta | 7 + 7 files changed, 1222 insertions(+), 15 deletions(-) create mode 100644 Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity create mode 100644 Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity.meta create mode 100644 Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity create mode 100644 Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity.meta diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs index 0281f3e4..bb7042a0 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs @@ -20,10 +20,10 @@ protected override void Init() _camera = GetComponent(); _camera.fieldOfView = _fov; - _rt = new RenderTexture(_resolution.x, _resolution.y, 32, RenderTextureFormat.ARGBFloat); + _rt = new RenderTexture(_resolution.x, _resolution.y, 32, RenderTextureFormat.ARGB32); _camera.targetTexture = _rt; - _texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBAFloat, false); + _texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBA32, false); } protected override void UpdateSensor() @@ -37,7 +37,8 @@ protected override void UpdateSensor() protected bool LoadTexture() { bool result = false; - AsyncGPUReadback.Request(_rt, 0, request => { + AsyncGPUReadback.Request(_rt, 0, request => + { if (request.hasError) { } diff --git a/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity b/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity new file mode 100644 index 00000000..cd142350 --- /dev/null +++ b/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity @@ -0,0 +1,714 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!29 &1 +OcclusionCullingSettings: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_OcclusionBakeSettings: + smallestOccluder: 5 + smallestHole: 0.25 + backfaceThreshold: 100 + m_SceneGUID: 00000000000000000000000000000000 + m_OcclusionCullingData: {fileID: 0} +--- !u!104 &2 +RenderSettings: + m_ObjectHideFlags: 0 + serializedVersion: 10 + m_Fog: 0 + m_FogColor: {r: 0.5, g: 0.5, b: 0.5, a: 1} + m_FogMode: 3 + m_FogDensity: 0.01 + m_LinearFogStart: 0 + m_LinearFogEnd: 300 + m_AmbientSkyColor: {r: 0.212, g: 0.227, b: 0.259, a: 1} + m_AmbientEquatorColor: {r: 0.114, g: 0.125, b: 0.133, a: 1} + m_AmbientGroundColor: {r: 0.047, g: 0.043, b: 0.035, a: 1} + m_AmbientIntensity: 1 + m_AmbientMode: 0 + m_SubtractiveShadowColor: {r: 0.42, g: 0.478, b: 0.627, a: 1} + m_SkyboxMaterial: {fileID: 10304, guid: 0000000000000000f000000000000000, type: 0} + m_HaloStrength: 0.5 + m_FlareStrength: 1 + m_FlareFadeSpeed: 3 + m_HaloTexture: {fileID: 0} + m_SpotCookie: {fileID: 10001, guid: 0000000000000000e000000000000000, type: 0} + m_DefaultReflectionMode: 0 + m_DefaultReflectionResolution: 128 + m_ReflectionBounces: 1 + m_ReflectionIntensity: 1 + m_CustomReflection: {fileID: 0} + m_Sun: {fileID: 0} + m_IndirectSpecularColor: {r: 0.18028378, g: 0.22571412, b: 0.30692285, a: 1} + m_UseRadianceAmbientProbe: 0 +--- !u!157 &3 +LightmapSettings: + m_ObjectHideFlags: 0 + serializedVersion: 12 + m_GISettings: + serializedVersion: 2 + m_BounceScale: 1 + m_IndirectOutputScale: 1 + m_AlbedoBoost: 1 + m_EnvironmentLightingMode: 0 + m_EnableBakedLightmaps: 1 + m_EnableRealtimeLightmaps: 0 + m_LightmapEditorSettings: + serializedVersion: 12 + m_Resolution: 2 + m_BakeResolution: 40 + m_AtlasSize: 1024 + m_AO: 0 + m_AOMaxDistance: 1 + m_CompAOExponent: 1 + m_CompAOExponentDirect: 0 + m_ExtractAmbientOcclusion: 0 + m_Padding: 2 + m_LightmapParameters: {fileID: 0} + m_LightmapsBakeMode: 1 + m_TextureCompression: 1 + m_ReflectionCompression: 2 + m_MixedBakeMode: 2 + m_BakeBackend: 1 + m_PVRSampling: 1 + m_PVRDirectSampleCount: 32 + m_PVRSampleCount: 512 + m_PVRBounces: 2 + m_PVREnvironmentSampleCount: 256 + m_PVREnvironmentReferencePointCount: 2048 + m_PVRFilteringMode: 1 + m_PVRDenoiserTypeDirect: 1 + m_PVRDenoiserTypeIndirect: 1 + m_PVRDenoiserTypeAO: 1 + m_PVRFilterTypeDirect: 0 + m_PVRFilterTypeIndirect: 0 + m_PVRFilterTypeAO: 0 + m_PVREnvironmentMIS: 1 + m_PVRCulling: 1 + m_PVRFilteringGaussRadiusDirect: 1 + m_PVRFilteringGaussRadiusIndirect: 5 + m_PVRFilteringGaussRadiusAO: 2 + m_PVRFilteringAtrousPositionSigmaDirect: 0.5 + m_PVRFilteringAtrousPositionSigmaIndirect: 2 + m_PVRFilteringAtrousPositionSigmaAO: 1 + m_ExportTrainingData: 0 + m_TrainingDataDestination: TrainingData + m_LightProbeSampleCountMultiplier: 4 + m_LightingDataAsset: {fileID: 20201, guid: 0000000000000000f000000000000000, type: 0} + m_LightingSettings: {fileID: 0} +--- !u!196 &4 +NavMeshSettings: + serializedVersion: 2 + m_ObjectHideFlags: 0 + m_BuildSettings: + serializedVersion: 3 + agentTypeID: 0 + agentRadius: 0.5 + agentHeight: 2 + agentSlope: 45 + agentClimb: 0.4 + ledgeDropHeight: 0 + maxJumpAcrossDistance: 0 + minRegionArea: 2 + manualCellSize: 0 + cellSize: 0.16666667 + manualTileSize: 0 + tileSize: 256 + buildHeightMesh: 0 + maxJobWorkers: 0 + preserveTilesOutsideBounds: 0 + debug: + m_Flags: 0 + m_NavMeshData: {fileID: 0} +--- !u!1 &62720512 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 62720515} + - component: {fileID: 62720514} + - component: {fileID: 62720513} + m_Layer: 0 + m_Name: Main Camera + m_TagString: MainCamera + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!81 &62720513 +AudioListener: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 62720512} + m_Enabled: 1 +--- !u!20 &62720514 +Camera: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 62720512} + m_Enabled: 1 + serializedVersion: 2 + m_ClearFlags: 1 + m_BackGroundColor: {r: 0.19215687, g: 0.3019608, b: 0.4745098, a: 0} + m_projectionMatrixMode: 1 + m_GateFitMode: 2 + m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 + m_SensorSize: {x: 36, y: 24} + m_LensShift: {x: 0, y: 0} + m_NormalizedViewPortRect: + serializedVersion: 2 + x: 0 + y: 0 + width: 1 + height: 1 + near clip plane: 0.3 + far clip plane: 1000 + field of view: 60 + orthographic: 0 + orthographic size: 5 + m_Depth: 1 + m_CullingMask: + serializedVersion: 2 + m_Bits: 4294967295 + m_RenderingPath: -1 + m_TargetTexture: {fileID: 0} + m_TargetDisplay: 0 + m_TargetEye: 3 + m_HDR: 1 + m_AllowMSAA: 1 + m_AllowDynamicResolution: 0 + m_ForceIntoRT: 0 + m_OcclusionCulling: 1 + m_StereoConvergence: 10 + m_StereoSeparation: 0.022 +--- !u!4 &62720515 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 62720512} + serializedVersion: 2 + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 100, y: 1, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 0} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &135884633 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 135884635} + - component: {fileID: 135884634} + m_Layer: 0 + m_Name: Directional Light + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!108 &135884634 +Light: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 135884633} + m_Enabled: 1 + serializedVersion: 11 + m_Type: 1 + m_Color: {r: 1, g: 0.95686275, b: 0.8392157, a: 1} + m_Intensity: 1 + m_Range: 10 + m_SpotAngle: 30 + m_InnerSpotAngle: 21.80208 + m_CookieSize: 10 + m_Shadows: + m_Type: 2 + m_Resolution: -1 + m_CustomResolution: -1 + m_Strength: 1 + m_Bias: 0.05 + m_NormalBias: 0.4 + m_NearPlane: 0.2 + m_CullingMatrixOverride: + e00: 1 + e01: 0 + e02: 0 + e03: 0 + e10: 0 + e11: 1 + e12: 0 + e13: 0 + e20: 0 + e21: 0 + e22: 1 + e23: 0 + e30: 0 + e31: 0 + e32: 0 + e33: 1 + m_UseCullingMatrixOverride: 0 + m_Cookie: {fileID: 0} + m_DrawHalo: 0 + m_Flare: {fileID: 0} + m_RenderMode: 0 + m_CullingMask: + serializedVersion: 2 + m_Bits: 4294967295 + m_RenderingLayerMask: 1 + m_Lightmapping: 4 + m_LightShadowCasterMode: 0 + m_AreaSize: {x: 1, y: 1} + m_BounceIntensity: 1 + m_ColorTemperature: 6570 + m_UseColorTemperature: 0 + m_BoundingSphereOverride: {x: 0, y: 0, z: 0, w: 0} + m_UseBoundingSphereOverride: 0 + m_UseViewFrustumForShadowCasterCull: 1 + m_ShadowRadius: 0 + m_ShadowAngle: 0 +--- !u!4 &135884635 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 135884633} + serializedVersion: 2 + m_LocalRotation: {x: 0.40821788, y: -0.23456968, z: 0.10938163, w: 0.8754261} + m_LocalPosition: {x: 0, y: 3, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 0} + m_LocalEulerAnglesHint: {x: 50, y: -30, z: 0} +--- !u!1001 &189404109 +PrefabInstance: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_Modification: + serializedVersion: 3 + m_TransformParent: {fileID: 0} + m_Modifications: + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_RootOrder + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalPosition.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalPosition.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalPosition.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.w + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalEulerAnglesHint.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalEulerAnglesHint.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalEulerAnglesHint.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060223, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_Name + value: DemoEnv + objectReference: {fileID: 0} + m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 666016651} + m_AddedComponents: [] + m_SourcePrefab: {fileID: 100100000, guid: 581b84ef57339314c92df1cef0a06b47, type: 3} +--- !u!1 &492062520 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 492062521} + - component: {fileID: 492062523} + - component: {fileID: 492062522} + m_Layer: 5 + m_Name: ColorImage + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!224 &492062521 +RectTransform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 492062520} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 1180426313} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} + m_AnchorMin: {x: 0.5, y: 0.5} + m_AnchorMax: {x: 0.5, y: 0.5} + m_AnchoredPosition: {x: 0, y: 0} + m_SizeDelta: {x: 640, y: 480} + m_Pivot: {x: 0.5, y: 0.5} +--- !u!114 &492062522 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 492062520} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 1344c3c82d62a2a41a3576d8abb8e3ea, type: 3} + m_Name: + m_EditorClassIdentifier: + m_Material: {fileID: 0} + m_Color: {r: 1, g: 1, b: 1, a: 1} + m_RaycastTarget: 1 + m_RaycastPadding: {x: 0, y: 0, z: 0, w: 0} + m_Maskable: 1 + m_OnCullStateChanged: + m_PersistentCalls: + m_Calls: [] + m_Texture: {fileID: 0} + m_UVRect: + serializedVersion: 2 + x: 0 + y: 0 + width: 1 + height: 1 +--- !u!222 &492062523 +CanvasRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 492062520} + m_CullTransparentMesh: 1 +--- !u!1001 &666016650 +PrefabInstance: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_Modification: + serializedVersion: 3 + m_TransformParent: {fileID: 1454009686} + m_Modifications: + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalPosition.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalPosition.y + value: 1.6 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalPosition.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalRotation.w + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalRotation.x + value: -0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalRotation.y + value: -0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalRotation.z + value: -0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalEulerAnglesHint.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalEulerAnglesHint.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_LocalEulerAnglesHint.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 1785895639420286579, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: m_Name + value: RGBDCamera + objectReference: {fileID: 0} + m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: [] + m_AddedComponents: [] + m_SourcePrefab: {fileID: 100100000, guid: 6a2c732697fa6da47999dd17b096ab09, type: 3} +--- !u!4 &666016651 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + m_PrefabInstance: {fileID: 666016650} + m_PrefabAsset: {fileID: 0} +--- !u!1 &1180426309 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 1180426313} + - component: {fileID: 1180426312} + - component: {fileID: 1180426311} + - component: {fileID: 1180426310} + m_Layer: 5 + m_Name: Canvas + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!114 &1180426310 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1180426309} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: dc42784cf147c0c48a680349fa168899, type: 3} + m_Name: + m_EditorClassIdentifier: + m_IgnoreReversedGraphics: 1 + m_BlockingObjects: 0 + m_BlockingMask: + serializedVersion: 2 + m_Bits: 4294967295 +--- !u!114 &1180426311 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1180426309} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 0cd44c1031e13a943bb63640046fad76, type: 3} + m_Name: + m_EditorClassIdentifier: + m_UiScaleMode: 1 + m_ReferencePixelsPerUnit: 100 + m_ScaleFactor: 1 + m_ReferenceResolution: {x: 1920, y: 1080} + m_ScreenMatchMode: 0 + m_MatchWidthOrHeight: 1 + m_PhysicalUnit: 3 + m_FallbackScreenDPI: 96 + m_DefaultSpriteDPI: 96 + m_DynamicPixelsPerUnit: 1 + m_PresetInfoIsWorld: 0 +--- !u!223 &1180426312 +Canvas: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1180426309} + m_Enabled: 1 + serializedVersion: 3 + m_RenderMode: 0 + m_Camera: {fileID: 0} + m_PlaneDistance: 100 + m_PixelPerfect: 0 + m_ReceivesEvents: 1 + m_OverrideSorting: 0 + m_OverridePixelPerfect: 0 + m_SortingBucketNormalizedSize: 0 + m_VertexColorAlwaysGammaSpace: 0 + m_AdditionalShaderChannelsFlag: 0 + m_UpdateRectTransformForStandalone: 0 + m_SortingLayerID: 0 + m_SortingOrder: 0 + m_TargetDisplay: 0 +--- !u!224 &1180426313 +RectTransform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1180426309} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 0, y: 0, z: 0} + m_ConstrainProportionsScale: 0 + m_Children: + - {fileID: 492062521} + m_Father: {fileID: 0} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} + m_AnchorMin: {x: 0, y: 0} + m_AnchorMax: {x: 0, y: 0} + m_AnchoredPosition: {x: 0, y: 0} + m_SizeDelta: {x: 0, y: 0} + m_Pivot: {x: 0, y: 0} +--- !u!4 &1454009686 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + m_PrefabInstance: {fileID: 189404109} + m_PrefabAsset: {fileID: 0} +--- !u!1 &1489775038 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 1489775041} + - component: {fileID: 1489775040} + - component: {fileID: 1489775039} + m_Layer: 0 + m_Name: EventSystem + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!114 &1489775039 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1489775038} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 4f231c4fb786f3946a6b90b886c48677, type: 3} + m_Name: + m_EditorClassIdentifier: + m_SendPointerHoverToParent: 1 + m_HorizontalAxis: Horizontal + m_VerticalAxis: Vertical + m_SubmitButton: Submit + m_CancelButton: Cancel + m_InputActionsPerSecond: 10 + m_RepeatDelay: 0.5 + m_ForceModuleActive: 0 +--- !u!114 &1489775040 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1489775038} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 76c392e42b5098c458856cdf6ecaaaa1, type: 3} + m_Name: + m_EditorClassIdentifier: + m_FirstSelected: {fileID: 0} + m_sendNavigationEvents: 1 + m_DragThreshold: 10 +--- !u!4 &1489775041 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1489775038} + serializedVersion: 2 + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 0} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1660057539 &9223372036854775807 +SceneRoots: + m_ObjectHideFlags: 0 + m_Roots: + - {fileID: 135884635} + - {fileID: 189404109} + - {fileID: 1180426313} + - {fileID: 1489775041} + - {fileID: 62720515} diff --git a/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity.meta b/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity.meta new file mode 100644 index 00000000..9b6dcc5e --- /dev/null +++ b/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity.meta @@ -0,0 +1,7 @@ +fileFormatVersion: 2 +guid: d27dcc077d0763f449784b6aad5af7a1 +DefaultImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab index 71092d82..a0549828 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab @@ -30,7 +30,7 @@ Transform: m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4414791596585746458} serializedVersion: 2 - m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 @@ -123,9 +123,9 @@ MonoBehaviour: _frequency: 10 _topicName: /camera/info _serializer: - _source: {fileID: 0} + _source: {fileID: 6928715047789551323} _header: - _source: {fileID: 0} + _source: {fileID: 6928715047789551323} _frame_id: /camera_frame --- !u!114 &2224187045829796718 MonoBehaviour: @@ -143,7 +143,7 @@ MonoBehaviour: _topicName: /camera/depth/points _serializer: _header: - _source: {fileID: 0} + _source: {fileID: 6928715047789551323} _frame_id: /camera_frame _source: {fileID: 6928715047789551323} --- !u!114 &6110166055807567966 @@ -161,10 +161,10 @@ MonoBehaviour: _frequency: 10 _topicName: /camera/depth/image/compressed _serializer: - _source: {fileID: 0} + _source: {fileID: 6928715047789551323} _sourceTexture: 0 _header: - _source: {fileID: 0} + _source: {fileID: 6928715047789551323} _frame_id: /camera_frame quality: 75 --- !u!114 &8736958369943202624 @@ -182,9 +182,9 @@ MonoBehaviour: _frequency: 10 _topicName: /camera/color/image/compressed _serializer: - _source: {fileID: 0} + _source: {fileID: 6928715047789551323} _sourceTexture: 1 _header: - _source: {fileID: 0} + _source: {fileID: 6928715047789551323} _frame_id: /camera_frame quality: 75 diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs index 7fa8897a..e2b9189e 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs @@ -24,26 +24,31 @@ private enum SourceTexture [SerializeField] private HeaderSerializer _header; - [SerializeField, Range(1, 100)] - private int quality = 75; private ITextureInterface _sourceInterface; + private RenderTexture _tempRT; public override void Init() { base.Init(); _header.Init(); _sourceInterface = _source as ITextureInterface; - // _msg.format = "jpeg"; // FIXME: Depth image should not be compressed as jpeg. // It is normally encoded as 32FC1 and 16UC1, whose units are meters and millimeters respectively. // So we need a new serializer for depth images. + + _msg.encoding = "rgba8"; + _msg.is_bigendian = 0; + _msg.width = (uint)(_sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1).width; + _msg.height = (uint)(_sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1).height; + _msg.step = 1 * 4 * _msg.width; } public override ImageMsg Serialize() { _msg.header = _header.Serialize(); - _msg.data = (_sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1).EncodeToJPG(quality); + // FIXME: The image is upside down. + _msg.data = (_sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1).GetRawTextureData(); return _msg; } } diff --git a/Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity b/Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity new file mode 100644 index 00000000..25172a41 --- /dev/null +++ b/Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity @@ -0,0 +1,473 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!29 &1 +OcclusionCullingSettings: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_OcclusionBakeSettings: + smallestOccluder: 5 + smallestHole: 0.25 + backfaceThreshold: 100 + m_SceneGUID: 00000000000000000000000000000000 + m_OcclusionCullingData: {fileID: 0} +--- !u!104 &2 +RenderSettings: + m_ObjectHideFlags: 0 + serializedVersion: 10 + m_Fog: 0 + m_FogColor: {r: 0.5, g: 0.5, b: 0.5, a: 1} + m_FogMode: 3 + m_FogDensity: 0.01 + m_LinearFogStart: 0 + m_LinearFogEnd: 300 + m_AmbientSkyColor: {r: 0.212, g: 0.227, b: 0.259, a: 1} + m_AmbientEquatorColor: {r: 0.114, g: 0.125, b: 0.133, a: 1} + m_AmbientGroundColor: {r: 0.047, g: 0.043, b: 0.035, a: 1} + m_AmbientIntensity: 1 + m_AmbientMode: 0 + m_SubtractiveShadowColor: {r: 0.42, g: 0.478, b: 0.627, a: 1} + m_SkyboxMaterial: {fileID: 10304, guid: 0000000000000000f000000000000000, type: 0} + m_HaloStrength: 0.5 + m_FlareStrength: 1 + m_FlareFadeSpeed: 3 + m_HaloTexture: {fileID: 0} + m_SpotCookie: {fileID: 10001, guid: 0000000000000000e000000000000000, type: 0} + m_DefaultReflectionMode: 0 + m_DefaultReflectionResolution: 128 + m_ReflectionBounces: 1 + m_ReflectionIntensity: 1 + m_CustomReflection: {fileID: 0} + m_Sun: {fileID: 0} + m_IndirectSpecularColor: {r: 0.18028378, g: 0.22571412, b: 0.30692285, a: 1} + m_UseRadianceAmbientProbe: 0 +--- !u!157 &3 +LightmapSettings: + m_ObjectHideFlags: 0 + serializedVersion: 12 + m_GISettings: + serializedVersion: 2 + m_BounceScale: 1 + m_IndirectOutputScale: 1 + m_AlbedoBoost: 1 + m_EnvironmentLightingMode: 0 + m_EnableBakedLightmaps: 1 + m_EnableRealtimeLightmaps: 0 + m_LightmapEditorSettings: + serializedVersion: 12 + m_Resolution: 2 + m_BakeResolution: 40 + m_AtlasSize: 1024 + m_AO: 0 + m_AOMaxDistance: 1 + m_CompAOExponent: 1 + m_CompAOExponentDirect: 0 + m_ExtractAmbientOcclusion: 0 + m_Padding: 2 + m_LightmapParameters: {fileID: 0} + m_LightmapsBakeMode: 1 + m_TextureCompression: 1 + m_ReflectionCompression: 2 + m_MixedBakeMode: 2 + m_BakeBackend: 1 + m_PVRSampling: 1 + m_PVRDirectSampleCount: 32 + m_PVRSampleCount: 512 + m_PVRBounces: 2 + m_PVREnvironmentSampleCount: 256 + m_PVREnvironmentReferencePointCount: 2048 + m_PVRFilteringMode: 1 + m_PVRDenoiserTypeDirect: 1 + m_PVRDenoiserTypeIndirect: 1 + m_PVRDenoiserTypeAO: 1 + m_PVRFilterTypeDirect: 0 + m_PVRFilterTypeIndirect: 0 + m_PVRFilterTypeAO: 0 + m_PVREnvironmentMIS: 1 + m_PVRCulling: 1 + m_PVRFilteringGaussRadiusDirect: 1 + m_PVRFilteringGaussRadiusIndirect: 5 + m_PVRFilteringGaussRadiusAO: 2 + m_PVRFilteringAtrousPositionSigmaDirect: 0.5 + m_PVRFilteringAtrousPositionSigmaIndirect: 2 + m_PVRFilteringAtrousPositionSigmaAO: 1 + m_ExportTrainingData: 0 + m_TrainingDataDestination: TrainingData + m_LightProbeSampleCountMultiplier: 4 + m_LightingDataAsset: {fileID: 20201, guid: 0000000000000000f000000000000000, type: 0} + m_LightingSettings: {fileID: 0} +--- !u!196 &4 +NavMeshSettings: + serializedVersion: 2 + m_ObjectHideFlags: 0 + m_BuildSettings: + serializedVersion: 3 + agentTypeID: 0 + agentRadius: 0.5 + agentHeight: 2 + agentSlope: 45 + agentClimb: 0.4 + ledgeDropHeight: 0 + maxJumpAcrossDistance: 0 + minRegionArea: 2 + manualCellSize: 0 + cellSize: 0.16666667 + manualTileSize: 0 + tileSize: 256 + buildHeightMesh: 0 + maxJobWorkers: 0 + preserveTilesOutsideBounds: 0 + debug: + m_Flags: 0 + m_NavMeshData: {fileID: 0} +--- !u!1 &62720512 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 62720515} + - component: {fileID: 62720514} + - component: {fileID: 62720513} + m_Layer: 0 + m_Name: Main Camera + m_TagString: MainCamera + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!81 &62720513 +AudioListener: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 62720512} + m_Enabled: 1 +--- !u!20 &62720514 +Camera: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 62720512} + m_Enabled: 1 + serializedVersion: 2 + m_ClearFlags: 1 + m_BackGroundColor: {r: 0.19215687, g: 0.3019608, b: 0.4745098, a: 0} + m_projectionMatrixMode: 1 + m_GateFitMode: 2 + m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 + m_SensorSize: {x: 36, y: 24} + m_LensShift: {x: 0, y: 0} + m_NormalizedViewPortRect: + serializedVersion: 2 + x: 0 + y: 0 + width: 1 + height: 1 + near clip plane: 0.3 + far clip plane: 1000 + field of view: 60 + orthographic: 0 + orthographic size: 5 + m_Depth: 1 + m_CullingMask: + serializedVersion: 2 + m_Bits: 4294967295 + m_RenderingPath: -1 + m_TargetTexture: {fileID: 0} + m_TargetDisplay: 0 + m_TargetEye: 3 + m_HDR: 1 + m_AllowMSAA: 1 + m_AllowDynamicResolution: 0 + m_ForceIntoRT: 0 + m_OcclusionCulling: 1 + m_StereoConvergence: 10 + m_StereoSeparation: 0.022 +--- !u!4 &62720515 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 62720512} + serializedVersion: 2 + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 1.6, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 1454009686} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &135884633 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 135884635} + - component: {fileID: 135884634} + m_Layer: 0 + m_Name: Directional Light + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!108 &135884634 +Light: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 135884633} + m_Enabled: 1 + serializedVersion: 11 + m_Type: 1 + m_Color: {r: 1, g: 0.95686275, b: 0.8392157, a: 1} + m_Intensity: 1 + m_Range: 10 + m_SpotAngle: 30 + m_InnerSpotAngle: 21.80208 + m_CookieSize: 10 + m_Shadows: + m_Type: 2 + m_Resolution: -1 + m_CustomResolution: -1 + m_Strength: 1 + m_Bias: 0.05 + m_NormalBias: 0.4 + m_NearPlane: 0.2 + m_CullingMatrixOverride: + e00: 1 + e01: 0 + e02: 0 + e03: 0 + e10: 0 + e11: 1 + e12: 0 + e13: 0 + e20: 0 + e21: 0 + e22: 1 + e23: 0 + e30: 0 + e31: 0 + e32: 0 + e33: 1 + m_UseCullingMatrixOverride: 0 + m_Cookie: {fileID: 0} + m_DrawHalo: 0 + m_Flare: {fileID: 0} + m_RenderMode: 0 + m_CullingMask: + serializedVersion: 2 + m_Bits: 4294967295 + m_RenderingLayerMask: 1 + m_Lightmapping: 4 + m_LightShadowCasterMode: 0 + m_AreaSize: {x: 1, y: 1} + m_BounceIntensity: 1 + m_ColorTemperature: 6570 + m_UseColorTemperature: 0 + m_BoundingSphereOverride: {x: 0, y: 0, z: 0, w: 0} + m_UseBoundingSphereOverride: 0 + m_UseViewFrustumForShadowCasterCull: 1 + m_ShadowRadius: 0 + m_ShadowAngle: 0 +--- !u!4 &135884635 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 135884633} + serializedVersion: 2 + m_LocalRotation: {x: 0.40821788, y: -0.23456968, z: 0.10938163, w: 0.8754261} + m_LocalPosition: {x: 0, y: 3, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 0} + m_LocalEulerAnglesHint: {x: 50, y: -30, z: 0} +--- !u!1001 &189404109 +PrefabInstance: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_Modification: + serializedVersion: 3 + m_TransformParent: {fileID: 0} + m_Modifications: + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_RootOrder + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalPosition.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalPosition.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalPosition.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.w + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalRotation.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalEulerAnglesHint.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalEulerAnglesHint.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_LocalEulerAnglesHint.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 2848956545337060223, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + propertyPath: m_Name + value: DemoEnv + objectReference: {fileID: 0} + m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 511013365} + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 62720515} + m_AddedComponents: [] + m_SourcePrefab: {fileID: 100100000, guid: 581b84ef57339314c92df1cef0a06b47, type: 3} +--- !u!1001 &511013364 +PrefabInstance: + m_ObjectHideFlags: 0 + serializedVersion: 2 + m_Modification: + serializedVersion: 3 + m_TransformParent: {fileID: 1454009686} + m_Modifications: + - target: {fileID: 4414791596585746458, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_Name + value: RGBDCamera_ros + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalPosition.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalPosition.y + value: 1.6 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalPosition.z + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalRotation.w + value: 1 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalRotation.x + value: -0 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalRotation.y + value: -0 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalRotation.z + value: -0 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalEulerAnglesHint.x + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalEulerAnglesHint.y + value: 0 + objectReference: {fileID: 0} + - target: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + propertyPath: m_LocalEulerAnglesHint.z + value: 0 + objectReference: {fileID: 0} + m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: [] + m_AddedComponents: [] + m_SourcePrefab: {fileID: 100100000, guid: caf455cab29d65c4491e901049b60dee, type: 3} +--- !u!4 &511013365 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 4414791596585746529, guid: caf455cab29d65c4491e901049b60dee, + type: 3} + m_PrefabInstance: {fileID: 511013364} + m_PrefabAsset: {fileID: 0} +--- !u!4 &1454009686 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + m_PrefabInstance: {fileID: 189404109} + m_PrefabAsset: {fileID: 0} +--- !u!1660057539 &9223372036854775807 +SceneRoots: + m_ObjectHideFlags: 0 + m_Roots: + - {fileID: 135884635} + - {fileID: 189404109} diff --git a/Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity.meta b/Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity.meta new file mode 100644 index 00000000..23a9b8a1 --- /dev/null +++ b/Assets/UnitySensorsROS/Samples/Camera/Demo_RGBDCamera_ros.unity.meta @@ -0,0 +1,7 @@ +fileFormatVersion: 2 +guid: 228f85eaabecbf14d941e4f52feda514 +DefaultImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: From 560495af32bed0a07ce6dd95082f848d31e0de03 Mon Sep 17 00:00:00 2001 From: chy <1274653465@qq.com> Date: Tue, 19 Nov 2024 00:38:22 +0800 Subject: [PATCH 09/15] Updated ImageMsgSerializer to flip images and support rgb8 and 32fc1 encoding --- .../Interfaces/Sensor/ITextureInterface.cs | 1 + .../Camera/DepthCamera/DepthCameraSensor.cs | 2 + .../Camera/RGBCamera/RGBCameraSensor.cs | 2 + .../Camera/RGBDCamera/RGBDCameraSensor.cs | 1 + .../SensorMsgs/ImageMsgSerializer.cs | 83 +++++++++++++++++-- 5 files changed, 83 insertions(+), 6 deletions(-) diff --git a/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/ITextureInterface.cs b/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/ITextureInterface.cs index b354e783..0e8c0b5f 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/ITextureInterface.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/ITextureInterface.cs @@ -6,6 +6,7 @@ public interface ITextureInterface { public Texture2D texture0 { get; } public Texture2D texture1 { get; } + public float texture0FarClipPlane { get; } // public byte[] data { get; } // public int width { get; } diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs index 53566bbf..4317f32d 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs @@ -47,6 +47,8 @@ public class DepthCameraSensor : CameraSensor, ITextureInterface, IPointCloudInt public PointCloud pointCloud { get => _pointCloud; } public int pointsNum { get => _pointsNum; } + public float texture0FarClipPlane { get => _camera.farClipPlane; } + protected override void Init() { _camera = GetComponent(); diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs index bb7042a0..1032012d 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs @@ -15,6 +15,8 @@ public class RGBCameraSensor : CameraSensor, ITextureInterface public Texture2D texture0 { get => _texture; } public Texture2D texture1 { get => _texture; } + public float texture0FarClipPlane { get => _camera.farClipPlane; } + protected override void Init() { _camera = GetComponent(); diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs index a55665b7..36e86d63 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs @@ -51,6 +51,7 @@ public class RGBDCameraSensor : CameraSensor, ITextureInterface, IPointCloudInte public Texture2D texture1 { get => _colorTexture; } public PointCloud pointCloud { get => _pointCloud; } public int pointsNum { get => _pointsNum; } + public float texture0FarClipPlane { get => _depthCamera.farClipPlane; } protected override void Init() { diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs index e2b9189e..45c7e4bf 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs @@ -16,17 +16,28 @@ private enum SourceTexture Texture0, Texture1 } + private enum Encoding + { + _RGB8, + _32FC1, + // TODO: Support 16UC1 encoding + } [SerializeField, Interface(typeof(ITextureInterface))] private Object _source; [SerializeField] private SourceTexture _sourceTexture; + [SerializeField] + private Encoding _encoding; [SerializeField] private HeaderSerializer _header; private ITextureInterface _sourceInterface; - private RenderTexture _tempRT; + private Texture2D _flippedTexture; + private Color[] _pixels; + private Color[] _pixelsRow; + private float distanceFactor; public override void Init() { @@ -37,19 +48,79 @@ public override void Init() // It is normally encoded as 32FC1 and 16UC1, whose units are meters and millimeters respectively. // So we need a new serializer for depth images. - _msg.encoding = "rgba8"; + var texture = _sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1; + Debug.Log("FarClipPlane: " + _sourceInterface.texture0FarClipPlane); + + uint bytesPerPixel; + TextureFormat textureFormat; + switch (_encoding) + { + case Encoding._32FC1: + _msg.encoding = "32FC1"; + bytesPerPixel = 1 * 4; + textureFormat = TextureFormat.RFloat; + distanceFactor = _sourceInterface.texture0FarClipPlane; + break; + case Encoding._RGB8: + default: + _msg.encoding = "rgb8"; + bytesPerPixel = 3 * 1; + textureFormat = TextureFormat.RGB24; + distanceFactor = 1.0f; + break; + } + _msg.is_bigendian = 0; - _msg.width = (uint)(_sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1).width; - _msg.height = (uint)(_sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1).height; - _msg.step = 1 * 4 * _msg.width; + _msg.width = (uint)texture.width; + _msg.height = (uint)texture.height; + _msg.step = bytesPerPixel * _msg.width; + _msg.data = new byte[_msg.step * _msg.height]; + + _flippedTexture = new Texture2D(texture.width, texture.height, textureFormat, false); + + _pixels = new Color[texture.width * texture.height]; + _pixelsRow = new Color[texture.width]; } public override ImageMsg Serialize() { _msg.header = _header.Serialize(); // FIXME: The image is upside down. - _msg.data = (_sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1).GetRawTextureData(); + var texture = _sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1; + FlipTextureVertically(texture, _flippedTexture); + var byteNativeArray = _flippedTexture.GetRawTextureData(); + var colors = _flippedTexture.GetPixels(); + + + + // Manually copy the data to the message to avoid GC allocation + byteNativeArray.CopyTo(_msg.data); return _msg; } + private void FlipTextureVertically(Texture2D sourceTexture, Texture2D targetTexture) + { + // TODO: Use a shader to flip the texture + int width = sourceTexture.width; + int height = sourceTexture.height; + // var colorNativeArray = sourceTexture.GetPixelData(0); + // Manually copy the data to the message to avoid GC allocation + // colorNativeArray.CopyTo(_pixels); + + // FIXME: Performance issue + _pixels = sourceTexture.GetPixels(0); + + for (int j = 0; j < height / 2; j++) + { + System.Array.Copy(_pixels, j * width, _pixelsRow, 0, width); + System.Array.Copy(_pixels, (height - j - 1) * width, _pixels, j * width, width); + System.Array.Copy(_pixelsRow, 0, _pixels, (height - j - 1) * width, width); + } + for (int i = 0; i < _pixels.Length; i++) + { + _pixels[i] *= distanceFactor; + } + targetTexture.SetPixels(_pixels); + targetTexture.Apply(); + } } } From 29e0c9adb6a472d133bdef04042e05e1627329a7 Mon Sep 17 00:00:00 2001 From: DESKTOP-E4VIK7O <1274653465@qq.com> Date: Tue, 19 Nov 2024 16:02:54 +0800 Subject: [PATCH 10/15] Removed distance inversion from DepthBufferLidar shader and related scripts; added GPU read error logging to DepthCameraSensor; updated RaycastCommand API in IUpdateRaycastCommandsJob; added UnitySensorsROS to Some sensor prefabs; added Raycast LayerMask in RaycastLiDARSensor. --- .../Prefabs/LiDAR/Livox/Mid-360.prefab | 13 +- .../Prefabs/LiDAR/Velodyne/VLP-16.prefab | 21 +- .../Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab | 21 +- .../Prefabs/LiDAR/Velodyne/VLP-32.prefab | 21 +- .../Camera/DepthCamera/DepthCameraSensor.cs | 2 + .../DepthBufferLiDAR/ITextureToPointsJob.cs | 3 +- .../RaycastLiDAR/IUpdateRaycastCommandsJob.cs | 8 +- .../LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs | 9 +- .../Runtime/Shaders/DepthBufferLidar.shader | 3 +- .../Samples/LiDAR/Velodyne/Demo_VLP-16.unity | 56 ++- .../Demo_VLS-128_with_DepthBuffer.unity | 61 ++- .../Prefabs/Camera/DepthCamera_ros.prefab | 12 +- .../Prefabs/Camera/RGBDCamera_ros.prefab | 10 +- .../Prefabs/LiDAR/Livox/Mid-360_ros.prefab | 13 +- .../Prefabs/LiDAR/Velodyne/VLP-16_ros.prefab | 21 +- .../VLS-128_with_DepthBuffer_ros.prefab | 399 ++++++++++++++++++ .../VLS-128_with_DepthBuffer_ros.prefab.meta | 7 + .../CompressedImageMsgSerializer.cs | 3 - .../SensorMsgs/ImageMsgSerializer.cs | 120 ++++-- 19 files changed, 683 insertions(+), 120 deletions(-) create mode 100644 Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab create mode 100644 Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab.meta diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab index 9be36d50..eef2cac4 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9210621271187283373} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0.047, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 9210621271816118166} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &9210621271187283363 MonoBehaviour: @@ -52,6 +52,9 @@ MonoBehaviour: _maxRange: 70 _gaussianNoiseSigma: 0.02 _maxIntensity: 255 + _raycastLayerMask: + serializedVersion: 2 + m_Bits: 1 --- !u!114 &3771061048342558472 MonoBehaviour: m_ObjectHideFlags: 0 @@ -90,13 +93,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9210621271227589044} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0.0261, z: 0} m_LocalScale: {x: 0.001, y: 0.001, z: 0.001} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 9210621272520305481} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &9210621271227589035 MeshFilter: @@ -123,6 +126,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -171,6 +176,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9210621271816118161} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -179,7 +185,6 @@ Transform: - {fileID: 9210621271187283362} - {fileID: 9210621272520305481} m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &9210621272520305480 GameObject: @@ -204,6 +209,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 9210621272520305480} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -211,5 +217,4 @@ Transform: m_Children: - {fileID: 9210621271227589045} m_Father: {fileID: 9210621271816118166} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab index 7dff3d30..87555dcd 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5955675791944382927} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0643, z: 0} m_LocalScale: {x: 0.1033, y: 0.0074, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5955675793504985703} - m_RootOrder: 2 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &5955675791944382924 MeshFilter: @@ -58,6 +58,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -108,13 +110,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5955675792109571646} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0378, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5955675793856834622} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &5955675792109571644 MonoBehaviour: @@ -135,6 +137,9 @@ MonoBehaviour: _maxRange: 100 _gaussianNoiseSigma: 0.05 _maxIntensity: 255 + _raycastLayerMask: + serializedVersion: 2 + m_Bits: 1 --- !u!114 &5955675792109571645 MonoBehaviour: m_ObjectHideFlags: 0 @@ -173,13 +178,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5955675793193326067} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.03785, z: 0} m_LocalScale: {x: 0.1033, y: 0.01905, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5955675793504985703} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &5955675793193326064 MeshFilter: @@ -206,6 +211,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -254,6 +261,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5955675793504985696} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -263,7 +271,6 @@ Transform: - {fileID: 5955675793193326066} - {fileID: 5955675791944382926} m_Father: {fileID: 5955675793856834622} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &5955675793604380114 GameObject: @@ -290,13 +297,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5955675793604380114} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0094, z: 0} m_LocalScale: {x: 0.1033, y: 0.0094, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5955675793504985703} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &5955675793604380119 MeshFilter: @@ -323,6 +330,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -371,6 +380,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5955675793856834623} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -379,5 +389,4 @@ Transform: - {fileID: 5955675792109571651} - {fileID: 5955675793504985703} m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab index 6f0263f3..422008b6 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab @@ -23,6 +23,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5738741471255503641} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -31,7 +32,6 @@ Transform: - {fileID: 5738741472997638501} - {fileID: 5738741471667285313} m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &5738741471505844980 GameObject: @@ -58,13 +58,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5738741471505844980} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0094, z: 0} m_LocalScale: {x: 0.1033, y: 0.0094, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5738741471667285313} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &5738741471505844977 MeshFilter: @@ -91,6 +91,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -139,6 +141,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5738741471667285318} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -148,7 +151,6 @@ Transform: - {fileID: 5738741471916874452} - {fileID: 5738741473100887784} m_Father: {fileID: 5738741471255503640} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &5738741471916874453 GameObject: @@ -175,13 +177,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5738741471916874453} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0384, z: 0} m_LocalScale: {x: 0.1033, y: 0.0196, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5738741471667285313} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &5738741471916874454 MeshFilter: @@ -208,6 +210,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -258,13 +262,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5738741472997638424} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0377, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5738741471255503640} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &5738741472997638426 MonoBehaviour: @@ -285,6 +289,9 @@ MonoBehaviour: _maxRange: 100 _gaussianNoiseSigma: 0.05 _maxIntensity: 255 + _raycastLayerMask: + serializedVersion: 2 + m_Bits: 1 --- !u!114 &2499637783975528950 MonoBehaviour: m_ObjectHideFlags: 0 @@ -323,13 +330,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5738741473100887785} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.06535, z: 0} m_LocalScale: {x: 0.1033, y: 0.00735, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 5738741471667285313} - m_RootOrder: 2 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &5738741473100887786 MeshFilter: @@ -356,6 +363,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab index a9aa0659..3395904d 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4239717977722247699} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0373, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 4239717978122745875} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &4239717977722247697 MonoBehaviour: @@ -52,6 +52,9 @@ MonoBehaviour: _maxRange: 100 _gaussianNoiseSigma: 0.05 _maxIntensity: 255 + _raycastLayerMask: + serializedVersion: 2 + m_Bits: 1 --- !u!114 &4947725978431309543 MonoBehaviour: m_ObjectHideFlags: 0 @@ -90,13 +93,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4239717977887452642} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.07315, z: 0} m_LocalScale: {x: 0.1033, y: 0.01375, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 4239717978606450250} - m_RootOrder: 2 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &4239717977887452641 MeshFilter: @@ -123,6 +126,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -171,6 +176,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4239717978122745874} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -179,7 +185,6 @@ Transform: - {fileID: 4239717977722247790} - {fileID: 4239717978606450250} m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &4239717978373083647 GameObject: @@ -206,13 +211,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4239717978373083647} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.00745, z: 0} m_LocalScale: {x: 0.1033, y: 0.00745, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 4239717978606450250} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &4239717978373083642 MeshFilter: @@ -239,6 +244,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -287,6 +294,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4239717978606450253} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -296,7 +304,6 @@ Transform: - {fileID: 4239717978784072159} - {fileID: 4239717977887452643} m_Father: {fileID: 4239717978122745875} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &4239717978784072158 GameObject: @@ -323,13 +330,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4239717978784072158} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.03715, z: 0} m_LocalScale: {x: 0.1033, y: 0.02225, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 4239717978606450250} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &4239717978784072157 MeshFilter: @@ -356,6 +363,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs index 4317f32d..b6d4cdd7 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs @@ -129,6 +129,7 @@ private bool LoadTexture() { if (request.hasError) { + Debug.LogError("GPU readback error detected."); } else { @@ -138,6 +139,7 @@ private bool LoadTexture() result = true; } }); + // TODO: Use coroutine to wait for the request AsyncGPUReadback.WaitAllRequests(); return result; } diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs index 93bfa98f..97a0abcc 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/ITextureToPointsJob.cs @@ -33,9 +33,8 @@ public struct ITextureToPointsJob : IJobParallelFor public void Execute(int index) { - // TODO: there is no need to invert the pixel color int pixelIndex = pixelIndices[index + indexOffset]; - float distance = (1.0f - Mathf.Clamp01(pixels.AsReadOnly()[pixelIndex].r)) * far; + float distance = pixels.AsReadOnly()[pixelIndex].r * far; float distance_noised = distance + noises[index]; distance = (near < distance && distance < far && near < distance_noised && distance_noised < far) ? distance_noised : 0; PointXYZI point = new PointXYZI() diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs index 205541cf..870cecca 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/IUpdateRaycastCommandsJob.cs @@ -16,16 +16,18 @@ public struct IUpdateRaycastCommandsJob : IJobParallelFor public Matrix4x4 localToWorldMatrix; [ReadOnly] public float maxRange; - [ReadOnly, NativeDisableParallelForRestriction] + [ReadOnly] + public QueryParameters queryParameters; + [ReadOnly] public NativeArray directions; [ReadOnly] public int indexOffset; + [WriteOnly] public NativeArray raycastCommands; public void Execute(int index) { - // FIXME: Update the api - raycastCommands[index] = new RaycastCommand(origin, localToWorldMatrix * (Vector3)directions[index + indexOffset], maxRange); + raycastCommands[index] = new(origin, localToWorldMatrix * (Vector3)directions[index + indexOffset], queryParameters, maxRange); } } } \ No newline at end of file diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs index 18c53cae..ca9cf84d 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs @@ -13,6 +13,7 @@ namespace UnitySensors.Sensor.LiDAR { public class RaycastLiDARSensor : LiDARSensor { + [SerializeField] private LayerMask _raycastLayerMask = 1; private Transform _transform; private JobHandle _jobHandle; @@ -24,7 +25,7 @@ public class RaycastLiDARSensor : LiDARSensor private NativeArray _directions; private NativeArray _raycastCommands; private NativeArray _raycastHits; - + private NativeArray _noises; protected override void Init() @@ -40,7 +41,7 @@ protected override void Init() private void LoadScanData() { _directions = new NativeArray(scanPattern.size * 2, Allocator.Persistent); - for(int i = 0; i < scanPattern.size; i++) + for (int i = 0; i < scanPattern.size; i++) { _directions[i] = _directions[i + scanPattern.size] = scanPattern.scans[i]; } @@ -57,9 +58,11 @@ private void SetupJobs() origin = _transform.position, localToWorldMatrix = _transform.localToWorldMatrix, maxRange = maxRange, + queryParameters = new() { layerMask = _raycastLayerMask }, directions = _directions, indexOffset = 0, - raycastCommands = _raycastCommands + raycastCommands = _raycastCommands, + }; _updateGaussianNoisesJob = new IUpdateGaussianNoisesJob() diff --git a/Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader b/Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader index c62e0d8e..0a027ce1 100644 --- a/Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader +++ b/Assets/UnitySensors/Runtime/Shaders/DepthBufferLidar.shader @@ -55,8 +55,7 @@ Shader "UnitySensors/DepthBufferLidar" float depth01 = Linear01Depth(tex2D(_CameraDepthTexture, float2 (i.uv.x, (i.uv.y - _Y_MIN) * _Y_COEF)).r); float3 viewPos = (i.viewDir.xyz / i.viewDir.w) * depth01; - // TODO: there is no need to invert the pixel color - float distance = 1.0f - length(viewPos) / _F; + float distance = length(viewPos) / _F; return float4(distance, distance, distance, 1.0f); } ENDCG diff --git a/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLP-16.unity b/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLP-16.unity index 84f58e41..1b9d657c 100644 --- a/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLP-16.unity +++ b/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLP-16.unity @@ -13,7 +13,7 @@ OcclusionCullingSettings: --- !u!104 &2 RenderSettings: m_ObjectHideFlags: 0 - serializedVersion: 9 + serializedVersion: 10 m_Fog: 0 m_FogColor: {r: 0.5, g: 0.5, b: 0.5, a: 1} m_FogMode: 3 @@ -38,13 +38,12 @@ RenderSettings: m_ReflectionIntensity: 1 m_CustomReflection: {fileID: 0} m_Sun: {fileID: 0} - m_IndirectSpecularColor: {r: 0.44657898, g: 0.4964133, b: 0.5748178, a: 1} + m_IndirectSpecularColor: {r: 0.18028378, g: 0.22571412, b: 0.30692285, a: 1} m_UseRadianceAmbientProbe: 0 --- !u!157 &3 LightmapSettings: m_ObjectHideFlags: 0 serializedVersion: 12 - m_GIWorkflowMode: 1 m_GISettings: serializedVersion: 2 m_BounceScale: 1 @@ -67,9 +66,6 @@ LightmapSettings: m_LightmapParameters: {fileID: 0} m_LightmapsBakeMode: 1 m_TextureCompression: 1 - m_FinalGather: 0 - m_FinalGatherFiltering: 1 - m_FinalGatherRayCount: 256 m_ReflectionCompression: 2 m_MixedBakeMode: 2 m_BakeBackend: 1 @@ -97,14 +93,14 @@ LightmapSettings: m_ExportTrainingData: 0 m_TrainingDataDestination: TrainingData m_LightProbeSampleCountMultiplier: 4 - m_LightingDataAsset: {fileID: 0} + m_LightingDataAsset: {fileID: 20201, guid: 0000000000000000f000000000000000, type: 0} m_LightingSettings: {fileID: 0} --- !u!196 &4 NavMeshSettings: serializedVersion: 2 m_ObjectHideFlags: 0 m_BuildSettings: - serializedVersion: 2 + serializedVersion: 3 agentTypeID: 0 agentRadius: 0.5 agentHeight: 2 @@ -117,7 +113,7 @@ NavMeshSettings: cellSize: 0.16666667 manualTileSize: 0 tileSize: 256 - accuratePlacement: 0 + buildHeightMesh: 0 maxJobWorkers: 0 preserveTilesOutsideBounds: 0 debug: @@ -128,6 +124,7 @@ PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 1438717031} m_Modifications: - target: {fileID: 5955675793856834622, guid: 64ce6a702dcf5c549af554cb9b61453a, @@ -191,7 +188,16 @@ PrefabInstance: value: VLP-16 objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: [] + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: 64ce6a702dcf5c549af554cb9b61453a, type: 3} +--- !u!4 &860427553 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 5955675793856834622, guid: 64ce6a702dcf5c549af554cb9b61453a, + type: 3} + m_PrefabInstance: {fileID: 860427552} + m_PrefabAsset: {fileID: 0} --- !u!4 &1438717031 stripped Transform: m_CorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, @@ -238,9 +244,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -274,13 +288,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1481277607} + serializedVersion: 2 m_LocalRotation: {x: 0.2588191, y: 0, z: 0, w: 0.9659258} m_LocalPosition: {x: 0, y: 20, z: -25} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 30, y: 0, z: 0} --- !u!1 &1817644710 GameObject: @@ -307,9 +321,8 @@ Light: m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1817644710} m_Enabled: 1 - serializedVersion: 10 + serializedVersion: 11 m_Type: 1 - m_Shape: 0 m_Color: {r: 1, g: 0.95686275, b: 0.8392157, a: 1} m_Intensity: 1 m_Range: 10 @@ -368,19 +381,20 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1817644710} + serializedVersion: 2 m_LocalRotation: {x: 0.40821788, y: -0.23456968, z: 0.10938163, w: 0.8754261} m_LocalPosition: {x: 0, y: 3, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 50, y: -30, z: 0} --- !u!1001 &2848956545974690955 PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 0} m_Modifications: - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, @@ -444,4 +458,18 @@ PrefabInstance: value: DemoEnv objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 860427553} + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: 581b84ef57339314c92df1cef0a06b47, type: 3} +--- !u!1660057539 &9223372036854775807 +SceneRoots: + m_ObjectHideFlags: 0 + m_Roots: + - {fileID: 1481277610} + - {fileID: 1817644712} + - {fileID: 2848956545974690955} diff --git a/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity b/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity index b5903473..9427a851 100644 --- a/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity +++ b/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity @@ -13,7 +13,7 @@ OcclusionCullingSettings: --- !u!104 &2 RenderSettings: m_ObjectHideFlags: 0 - serializedVersion: 9 + serializedVersion: 10 m_Fog: 0 m_FogColor: {r: 0.5, g: 0.5, b: 0.5, a: 1} m_FogMode: 3 @@ -38,13 +38,12 @@ RenderSettings: m_ReflectionIntensity: 1 m_CustomReflection: {fileID: 0} m_Sun: {fileID: 0} - m_IndirectSpecularColor: {r: 0.44657898, g: 0.4964133, b: 0.5748178, a: 1} + m_IndirectSpecularColor: {r: 0.18028378, g: 0.22571412, b: 0.30692285, a: 1} m_UseRadianceAmbientProbe: 0 --- !u!157 &3 LightmapSettings: m_ObjectHideFlags: 0 serializedVersion: 12 - m_GIWorkflowMode: 1 m_GISettings: serializedVersion: 2 m_BounceScale: 1 @@ -67,9 +66,6 @@ LightmapSettings: m_LightmapParameters: {fileID: 0} m_LightmapsBakeMode: 1 m_TextureCompression: 1 - m_FinalGather: 0 - m_FinalGatherFiltering: 1 - m_FinalGatherRayCount: 256 m_ReflectionCompression: 2 m_MixedBakeMode: 2 m_BakeBackend: 1 @@ -97,14 +93,14 @@ LightmapSettings: m_ExportTrainingData: 0 m_TrainingDataDestination: TrainingData m_LightProbeSampleCountMultiplier: 4 - m_LightingDataAsset: {fileID: 0} + m_LightingDataAsset: {fileID: 20201, guid: 0000000000000000f000000000000000, type: 0} m_LightingSettings: {fileID: 0} --- !u!196 &4 NavMeshSettings: serializedVersion: 2 m_ObjectHideFlags: 0 m_BuildSettings: - serializedVersion: 2 + serializedVersion: 3 agentTypeID: 0 agentRadius: 0.5 agentHeight: 2 @@ -117,12 +113,18 @@ NavMeshSettings: cellSize: 0.16666667 manualTileSize: 0 tileSize: 256 - accuratePlacement: 0 + buildHeightMesh: 0 maxJobWorkers: 0 preserveTilesOutsideBounds: 0 debug: m_Flags: 0 m_NavMeshData: {fileID: 0} +--- !u!4 &816892473 stripped +Transform: + m_CorrespondingSourceObject: {fileID: 9219009777992118712, guid: aebab1e4472b99644b8adae9c42cc898, + type: 3} + m_PrefabInstance: {fileID: 3266885545265006758} + m_PrefabAsset: {fileID: 0} --- !u!4 &1438717031 stripped Transform: m_CorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, @@ -169,9 +171,17 @@ Camera: m_projectionMatrixMode: 1 m_GateFitMode: 2 m_FOVAxisMode: 0 + m_Iso: 200 + m_ShutterSpeed: 0.005 + m_Aperture: 16 + m_FocusDistance: 10 + m_FocalLength: 50 + m_BladeCount: 5 + m_Curvature: {x: 2, y: 11} + m_BarrelClipping: 0.25 + m_Anamorphism: 0 m_SensorSize: {x: 36, y: 24} m_LensShift: {x: 0, y: 0} - m_FocalLength: 50 m_NormalizedViewPortRect: serializedVersion: 2 x: 0 @@ -205,13 +215,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1481277607} + serializedVersion: 2 m_LocalRotation: {x: 0.2588191, y: 0, z: 0, w: 0.9659258} m_LocalPosition: {x: 0, y: 20, z: -25} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 30, y: 0, z: 0} --- !u!1 &1817644710 GameObject: @@ -238,9 +248,8 @@ Light: m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1817644710} m_Enabled: 1 - serializedVersion: 10 + serializedVersion: 11 m_Type: 1 - m_Shape: 0 m_Color: {r: 1, g: 0.95686275, b: 0.8392157, a: 1} m_Intensity: 1 m_Range: 10 @@ -299,19 +308,20 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 1817644710} + serializedVersion: 2 m_LocalRotation: {x: 0.40821788, y: -0.23456968, z: 0.10938163, w: 0.8754261} m_LocalPosition: {x: 0, y: 3, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 50, y: -30, z: 0} --- !u!1001 &2848956545974690955 PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 0} m_Modifications: - target: {fileID: 2848956545337060222, guid: 581b84ef57339314c92df1cef0a06b47, @@ -375,14 +385,27 @@ PrefabInstance: value: DemoEnv objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: + - targetCorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, + type: 3} + insertIndex: -1 + addedObject: {fileID: 816892473} + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: 581b84ef57339314c92df1cef0a06b47, type: 3} --- !u!1001 &3266885545265006758 PrefabInstance: m_ObjectHideFlags: 0 serializedVersion: 2 m_Modification: + serializedVersion: 3 m_TransformParent: {fileID: 1438717031} m_Modifications: + - target: {fileID: 9107878023928292438, guid: aebab1e4472b99644b8adae9c42cc898, + type: 3} + propertyPath: m_Enabled + value: 0 + objectReference: {fileID: 0} - target: {fileID: 9219009777992118712, guid: aebab1e4472b99644b8adae9c42cc898, type: 3} propertyPath: m_RootOrder @@ -444,4 +467,14 @@ PrefabInstance: value: VLS-128_with_DepthBuffer objectReference: {fileID: 0} m_RemovedComponents: [] + m_RemovedGameObjects: [] + m_AddedGameObjects: [] + m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: aebab1e4472b99644b8adae9c42cc898, type: 3} +--- !u!1660057539 &9223372036854775807 +SceneRoots: + m_ObjectHideFlags: 0 + m_Roots: + - {fileID: 1481277610} + - {fileID: 1817644712} + - {fileID: 2848956545974690955} diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab index 9614825c..70efb7b2 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab @@ -13,7 +13,7 @@ GameObject: - component: {fileID: 4853532333615571030} - component: {fileID: 4853532333615570985} - component: {fileID: 9201004833233192004} - - component: {fileID: 3086342091309557783} + - component: {fileID: 7171801529083048031} m_Layer: 0 m_Name: DepthCamera_ros m_TagString: Untagged @@ -29,7 +29,7 @@ Transform: m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 4853532333615571027} serializedVersion: 2 - m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 @@ -145,7 +145,7 @@ MonoBehaviour: _source: {fileID: 4853532333615571030} _frame_id: /camera_frame _source: {fileID: 4853532333615571030} ---- !u!114 &3086342091309557783 +--- !u!114 &7171801529083048031 MonoBehaviour: m_ObjectHideFlags: 0 m_CorrespondingSourceObject: {fileID: 0} @@ -154,15 +154,15 @@ MonoBehaviour: m_GameObject: {fileID: 4853532333615571027} m_Enabled: 1 m_EditorHideFlags: 0 - m_Script: {fileID: 11500000, guid: b474a6242e811f04488e3cb67b65dd35, type: 3} + m_Script: {fileID: 11500000, guid: e226440246ae84f438f484a93cb23d7c, type: 3} m_Name: m_EditorClassIdentifier: _frequency: 10 - _topicName: /camera/depth/image/compressed + _topicName: /camera/depth/image _serializer: _source: {fileID: 4853532333615571030} _sourceTexture: 0 + _encoding: 2 _header: _source: {fileID: 4853532333615571030} _frame_id: /camera_frame - quality: 75 diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab index a0549828..ee9d9115 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab @@ -13,7 +13,7 @@ GameObject: - component: {fileID: 6928715047789551323} - component: {fileID: 4414791596585746528} - component: {fileID: 2224187045829796718} - - component: {fileID: 6110166055807567966} + - component: {fileID: 6818158337698568988} - component: {fileID: 8736958369943202624} m_Layer: 0 m_Name: RGBDCamera_ros @@ -146,7 +146,7 @@ MonoBehaviour: _source: {fileID: 6928715047789551323} _frame_id: /camera_frame _source: {fileID: 6928715047789551323} ---- !u!114 &6110166055807567966 +--- !u!114 &6818158337698568988 MonoBehaviour: m_ObjectHideFlags: 0 m_CorrespondingSourceObject: {fileID: 0} @@ -155,18 +155,18 @@ MonoBehaviour: m_GameObject: {fileID: 4414791596585746458} m_Enabled: 1 m_EditorHideFlags: 0 - m_Script: {fileID: 11500000, guid: b474a6242e811f04488e3cb67b65dd35, type: 3} + m_Script: {fileID: 11500000, guid: e226440246ae84f438f484a93cb23d7c, type: 3} m_Name: m_EditorClassIdentifier: _frequency: 10 - _topicName: /camera/depth/image/compressed + _topicName: /camera/depth/image _serializer: _source: {fileID: 6928715047789551323} _sourceTexture: 0 + _encoding: 2 _header: _source: {fileID: 6928715047789551323} _frame_id: /camera_frame - quality: 75 --- !u!114 &8736958369943202624 MonoBehaviour: m_ObjectHideFlags: 0 diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Livox/Mid-360_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Livox/Mid-360_ros.prefab index 128a6fb5..fdf3bec5 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Livox/Mid-360_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Livox/Mid-360_ros.prefab @@ -23,6 +23,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 7522962571541571513} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -30,7 +31,6 @@ Transform: m_Children: - {fileID: 7522962572398341444} m_Father: {fileID: 7522962571841786727} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &7522962571841786720 GameObject: @@ -55,6 +55,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 7522962571841786720} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -63,7 +64,6 @@ Transform: - {fileID: 7522962572353966419} - {fileID: 7522962571541571512} m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &7522962572353966428 GameObject: @@ -90,13 +90,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 7522962572353966428} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0.047, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 7522962571841786727} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &7522962572353966418 MonoBehaviour: @@ -117,6 +117,9 @@ MonoBehaviour: _maxRange: 70 _gaussianNoiseSigma: 0.02 _maxIntensity: 255 + _raycastLayerMask: + serializedVersion: 2 + m_Bits: 1 --- !u!114 &7630058950724618500 MonoBehaviour: m_ObjectHideFlags: 0 @@ -161,13 +164,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 7522962572398341445} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0.0261, z: 0} m_LocalScale: {x: 0.001, y: 0.001, z: 0.001} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 7522962571541571512} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &7522962572398341466 MeshFilter: @@ -194,6 +197,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLP-16_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLP-16_ros.prefab index cbfc5818..840c90bd 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLP-16_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLP-16_ros.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 773861078525032441} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0094, z: 0} m_LocalScale: {x: 0.1033, y: 0.0094, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 773861078685929548} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &773861078525032444 MeshFilter: @@ -58,6 +58,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -106,6 +108,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 773861078685929547} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -115,7 +118,6 @@ Transform: - {fileID: 773861079472990169} - {fileID: 773861080117955557} m_Father: {fileID: 773861078808927765} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &773861078808927764 GameObject: @@ -140,6 +142,7 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 773861078808927764} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} @@ -148,7 +151,6 @@ Transform: - {fileID: 773861080551603304} - {fileID: 773861078685929548} m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!1 &773861079472990168 GameObject: @@ -175,13 +177,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 773861079472990168} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.03785, z: 0} m_LocalScale: {x: 0.1033, y: 0.01905, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 773861078685929548} - m_RootOrder: 1 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &773861079472990171 MeshFilter: @@ -208,6 +210,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -258,13 +262,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 773861080117955556} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0643, z: 0} m_LocalScale: {x: 0.1033, y: 0.0074, z: 0.1033} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 773861078685929548} - m_RootOrder: 2 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!33 &773861080117955559 MeshFilter: @@ -291,6 +295,8 @@ MeshRenderer: m_ReflectionProbeUsage: 1 m_RayTracingMode: 2 m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 m_RenderingLayerMask: 1 m_RendererPriority: 0 m_Materials: @@ -341,13 +347,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 773861080551603221} + serializedVersion: 2 m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} m_LocalPosition: {x: 0, y: 0.0378, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 773861078808927765} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &773861080551603223 MonoBehaviour: @@ -368,6 +374,9 @@ MonoBehaviour: _maxRange: 100 _gaussianNoiseSigma: 0.05 _maxIntensity: 255 + _raycastLayerMask: + serializedVersion: 2 + m_Bits: 1 --- !u!114 &2649015881702736681 MonoBehaviour: m_ObjectHideFlags: 0 diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab new file mode 100644 index 00000000..8d770c17 --- /dev/null +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab @@ -0,0 +1,399 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!1 &9219009776079660105 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 9219009776079660104} + - component: {fileID: 9219009776079660106} + - component: {fileID: 9219009776079660107} + m_Layer: 0 + m_Name: Cylinder + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &9219009776079660104 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009776079660105} + serializedVersion: 2 + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0.12065, z: 0} + m_LocalScale: {x: 0.1655, y: 0.02065, z: 0.1655} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 9219009777779736545} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!33 &9219009776079660106 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009776079660105} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &9219009776079660107 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009776079660105} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_StaticShadowCaster: 0 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 2100000, guid: 183a411708109c046b948a7f1e721b29, type: 2} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!1 &9219009776518534072 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 9219009776518534085} + - component: {fileID: 9219009776518534082} + - component: {fileID: 8926685048773102443} + m_Layer: 0 + m_Name: Sensor + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &9219009776518534085 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009776518534072} + serializedVersion: 2 + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0.06611, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 9219009777992118712} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!114 &9219009776518534082 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009776518534072} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 0e60e7cbad47e014d9f3454fea9529e5, type: 3} + m_Name: + m_EditorClassIdentifier: + _frequency: 10 + _scanPattern: {fileID: 11400000, guid: e4461be772cd0b7488ed536ecd21f9db, type: 2} + _pointsNumPerScan: 460800 + _minRange: 0.5 + _maxRange: 150 + _gaussianNoiseSigma: 0.1 + _maxIntensity: 255 + _texturePixelsNum: 1500000 + _textureSizePerCamera: {x: 0, y: 0} + _depthBufferLidarMat: {fileID: 2100000, guid: 4d25d3a0a13f3d9489db78fe07061f16, + type: 2} +--- !u!114 &8926685048773102443 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009776518534072} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 32c6ed908b3e5d74697c679c7798bcc2, type: 3} + m_Name: + m_EditorClassIdentifier: + _frequency: 10 + _topicName: /velodyne_points + _serializer: + _header: + _source: {fileID: 9219009776518534082} + _frame_id: velodyne_link + _source: {fileID: 9219009776518534082} +--- !u!1 &9219009777597040757 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 9219009777597040756} + - component: {fileID: 9219009777597040758} + - component: {fileID: 9219009777597040759} + m_Layer: 0 + m_Name: Cylinder + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &9219009777597040756 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777597040757} + serializedVersion: 2 + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0.067, z: 0} + m_LocalScale: {x: 0.1655, y: 0.0335, z: 0.1655} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 9219009777779736545} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!33 &9219009777597040758 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777597040757} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &9219009777597040759 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777597040757} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_StaticShadowCaster: 0 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 2100000, guid: b38b7d8f6cdc2834cb8d62fa8617f4b7, type: 2} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!1 &9219009777739667540 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 9219009777739667543} + - component: {fileID: 9219009777739667537} + - component: {fileID: 9219009777739667542} + m_Layer: 0 + m_Name: Cylinder + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &9219009777739667543 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777739667540} + serializedVersion: 2 + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0.0165, z: 0} + m_LocalScale: {x: 0.1655, y: 0.0165, z: 0.1655} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 9219009777779736545} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!33 &9219009777739667537 +MeshFilter: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777739667540} + m_Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} +--- !u!23 &9219009777739667542 +MeshRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777739667540} + m_Enabled: 1 + m_CastShadows: 1 + m_ReceiveShadows: 1 + m_DynamicOccludee: 1 + m_StaticShadowCaster: 0 + m_MotionVectors: 1 + m_LightProbeUsage: 1 + m_ReflectionProbeUsage: 1 + m_RayTracingMode: 2 + m_RayTraceProcedural: 0 + m_RayTracingAccelStructBuildFlagsOverride: 0 + m_RayTracingAccelStructBuildFlags: 1 + m_RenderingLayerMask: 1 + m_RendererPriority: 0 + m_Materials: + - {fileID: 2100000, guid: 183a411708109c046b948a7f1e721b29, type: 2} + m_StaticBatchInfo: + firstSubMesh: 0 + subMeshCount: 0 + m_StaticBatchRoot: {fileID: 0} + m_ProbeAnchor: {fileID: 0} + m_LightProbeVolumeOverride: {fileID: 0} + m_ScaleInLightmap: 1 + m_ReceiveGI: 1 + m_PreserveUVs: 0 + m_IgnoreNormalsForChartDetection: 0 + m_ImportantGI: 0 + m_StitchLightmapSeams: 1 + m_SelectedEditorRenderState: 3 + m_MinimumChartSize: 4 + m_AutoUVMaxDistance: 0.5 + m_AutoUVMaxAngle: 89 + m_LightmapParameters: {fileID: 0} + m_SortingLayerID: 0 + m_SortingLayer: 0 + m_SortingOrder: 0 + m_AdditionalVertexStreams: {fileID: 0} +--- !u!1 &9219009777779736550 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 9219009777779736545} + m_Layer: 0 + m_Name: Model + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &9219009777779736545 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777779736550} + serializedVersion: 2 + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: + - {fileID: 9219009777739667543} + - {fileID: 9219009777597040756} + - {fileID: 9219009776079660104} + m_Father: {fileID: 9219009777992118712} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &9219009777992118713 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 9219009777992118712} + m_Layer: 0 + m_Name: VLS-128_with_DepthBuffer_ros + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!4 &9219009777992118712 +Transform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 9219009777992118713} + serializedVersion: 2 + m_LocalRotation: {x: -0, y: -0, z: -0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: + - {fileID: 9219009776518534085} + - {fileID: 9219009777779736545} + m_Father: {fileID: 0} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab.meta b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab.meta new file mode 100644 index 00000000..b25c5a12 --- /dev/null +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer_ros.prefab.meta @@ -0,0 +1,7 @@ +fileFormatVersion: 2 +guid: d237c97cfa12ceb429f32c6afa7cbff2 +PrefabImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs index 65777f33..11dc8844 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/CompressedImageMsgSerializer.cs @@ -35,9 +35,6 @@ public override void Init() _header.Init(); _sourceInterface = _source as ITextureInterface; _msg.format = "jpeg"; - // FIXME: Depth image should not be compressed as jpeg. - // It is normally encoded as 32FC1 and 16UC1, whose units are meters and millimeters respectively. - // So we need a new serializer for depth images. } public override CompressedImageMsg Serialize() diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs index 45c7e4bf..ccdf7841 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs @@ -20,7 +20,21 @@ private enum Encoding { _RGB8, _32FC1, - // TODO: Support 16UC1 encoding + _16UC1 + } + private struct ColorRGB24 + { + public byte r; + public byte g; + public byte b; + } + private struct Color32FC1 + { + public float r; + } + private struct Color16UC1 + { + public ushort r; } [SerializeField, Interface(typeof(ITextureInterface))] @@ -35,21 +49,29 @@ private enum Encoding private ITextureInterface _sourceInterface; private Texture2D _flippedTexture; - private Color[] _pixels; - private Color[] _pixelsRow; private float distanceFactor; + private Color[] _sourcePixels; + private ColorRGB24[] _targetPixelsRGB24; + private Color32FC1[] _targetPixels32FC1; + private Color16UC1[] _targetPixels16UC1; + public override void Init() { base.Init(); _header.Init(); _sourceInterface = _source as ITextureInterface; - // FIXME: Depth image should not be compressed as jpeg. - // It is normally encoded as 32FC1 and 16UC1, whose units are meters and millimeters respectively. - // So we need a new serializer for depth images. var texture = _sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1; - Debug.Log("FarClipPlane: " + _sourceInterface.texture0FarClipPlane); + + if (texture.format != TextureFormat.RGBAFloat) + { + Debug.LogError("ImageMsgSerializer: Source texture format must be RGBAFloat"); + return; + } + + int width = texture.width; + int height = texture.height; uint bytesPerPixel; TextureFormat textureFormat; @@ -60,66 +82,92 @@ public override void Init() bytesPerPixel = 1 * 4; textureFormat = TextureFormat.RFloat; distanceFactor = _sourceInterface.texture0FarClipPlane; + _targetPixels32FC1 = new Color32FC1[width * height]; + break; + case Encoding._16UC1: + _msg.encoding = "16UC1"; + bytesPerPixel = 1 * 2; + textureFormat = TextureFormat.R16; + distanceFactor = _sourceInterface.texture0FarClipPlane * 1000; + _targetPixels16UC1 = new Color16UC1[width * height]; break; case Encoding._RGB8: default: _msg.encoding = "rgb8"; bytesPerPixel = 3 * 1; textureFormat = TextureFormat.RGB24; - distanceFactor = 1.0f; + distanceFactor = 1; + _targetPixelsRGB24 = new ColorRGB24[width * height]; break; } + _sourcePixels = new Color[width * height]; _msg.is_bigendian = 0; - _msg.width = (uint)texture.width; - _msg.height = (uint)texture.height; - _msg.step = bytesPerPixel * _msg.width; - _msg.data = new byte[_msg.step * _msg.height]; + _msg.width = (uint)width; + _msg.height = (uint)height; + _msg.step = (uint)(bytesPerPixel * width); + _msg.data = new byte[_msg.step * height]; - _flippedTexture = new Texture2D(texture.width, texture.height, textureFormat, false); + _flippedTexture = new Texture2D(width, height, textureFormat, false); - _pixels = new Color[texture.width * texture.height]; - _pixelsRow = new Color[texture.width]; } public override ImageMsg Serialize() { _msg.header = _header.Serialize(); - // FIXME: The image is upside down. var texture = _sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1; - FlipTextureVertically(texture, _flippedTexture); - var byteNativeArray = _flippedTexture.GetRawTextureData(); - var colors = _flippedTexture.GetPixels(); - + FlipTextureVertically(texture, _flippedTexture); // Manually copy the data to the message to avoid GC allocation - byteNativeArray.CopyTo(_msg.data); + _flippedTexture.GetRawTextureData().CopyTo(_msg.data); return _msg; } private void FlipTextureVertically(Texture2D sourceTexture, Texture2D targetTexture) { - // TODO: Use a shader to flip the texture + // TODO: Use shader or jobs to flip the texture int width = sourceTexture.width; int height = sourceTexture.height; - // var colorNativeArray = sourceTexture.GetPixelData(0); - // Manually copy the data to the message to avoid GC allocation - // colorNativeArray.CopyTo(_pixels); - // FIXME: Performance issue - _pixels = sourceTexture.GetPixels(0); + // Manually copy the data to the message to avoid GC allocation + sourceTexture.GetPixelData(0).CopyTo(_sourcePixels); - for (int j = 0; j < height / 2; j++) - { - System.Array.Copy(_pixels, j * width, _pixelsRow, 0, width); - System.Array.Copy(_pixels, (height - j - 1) * width, _pixels, j * width, width); - System.Array.Copy(_pixelsRow, 0, _pixels, (height - j - 1) * width, width); - } - for (int i = 0; i < _pixels.Length; i++) + switch (_encoding) { - _pixels[i] *= distanceFactor; + case Encoding._32FC1: + for (int j = 0; j < height; j++) + { + for (int i = 0; i < width; i++) + { + _targetPixels32FC1[j * width + i].r = _sourcePixels[(height - j - 1) * width + i].r * distanceFactor; + } + } + targetTexture.SetPixelData(_targetPixels32FC1, 0); + break; + case Encoding._16UC1: + for (int j = 0; j < height; j++) + { + for (int i = 0; i < width; i++) + { + _targetPixels16UC1[j * width + i].r = (ushort)(_sourcePixels[(height - j - 1) * width + i].r * distanceFactor); + } + } + targetTexture.SetPixelData(_targetPixels16UC1, 0); + break; + case Encoding._RGB8: + default: + for (int j = 0; j < height; j++) + { + for (int i = 0; i < width; i++) + { + _targetPixelsRGB24[j * width + i].r = (byte)(_sourcePixels[(height - j - 1) * width + i].r * 255); + _targetPixelsRGB24[j * width + i].g = (byte)(_sourcePixels[(height - j - 1) * width + i].g * 255); + _targetPixelsRGB24[j * width + i].b = (byte)(_sourcePixels[(height - j - 1) * width + i].b * 255); + } + } + targetTexture.SetPixelData(_targetPixelsRGB24, 0); + break; } - targetTexture.SetPixels(_pixels); targetTexture.Apply(); } } From 4e31334e39cb2ff6328291a900474a8e7bedd112 Mon Sep 17 00:00:00 2001 From: DESKTOP-E4VIK7O <1274653465@qq.com> Date: Tue, 19 Nov 2024 18:05:29 +0800 Subject: [PATCH 11/15] Holds the point cloud material reference in PointUtilitiesSO and replaces the PointUtilities class and updates the associated prefabs; remove redundant Usings --- .../Prefabs/LiDAR/Livox/Mid-360.prefab | 1 + .../Prefabs/LiDAR/Velodyne/VLP-16.prefab | 1 + .../Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab | 1 + .../Prefabs/LiDAR/Velodyne/VLP-32.prefab | 1 + .../Velodyne/VLS-128_with_DepthBuffer.prefab | 1 + .../ScriptableObjects/PointUtilitiesSO.asset | 20 +++++++++ .../PointUtilitiesSO.asset.meta | 8 ++++ .../Scripts/DataType/Geometry/Vector3D.cs | 2 - .../DataType/Sensor/PointCloud/PointXYZRGB.cs | 2 - .../Interfaces/Sensor/IImuDataInterface.cs | 2 - .../Sensor/PointCloud/IPointInterface.cs | 1 - .../Scripts/Sensors/Camera/CameraSensor.cs | 1 - .../Utils/Geometry/GeoCoordinateConverter.cs | 31 +++++++------ .../Utils/Noise/IUpdateGaussianNoisesJob.cs | 1 - .../Utils/PointCloud/PointUtilities.cs | 28 ------------ .../Utils/PointCloud/PointUtilities.cs.meta | 11 ----- .../Utils/PointCloud/PointUtilitiessSO.cs | 45 +++++++++++++++++++ .../PointCloud/PointUtilitiessSO.cs.meta | 2 + .../Sensor/PointCloudVisualizer.cs | 9 ++-- .../Runtime/Scripts/Visualizers/Visualizer.cs | 2 - .../SensorMsgs/PointCloud2MsgSerializer.cs | 6 +-- 21 files changed, 103 insertions(+), 73 deletions(-) create mode 100644 Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset create mode 100644 Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset.meta delete mode 100644 Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs delete mode 100644 Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs.meta create mode 100644 Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs create mode 100644 Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs.meta diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab index eef2cac4..36dbb679 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Livox/Mid-360.prefab @@ -67,6 +67,7 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: f2ac6256eabda88478ca2a2fc51a2c64, type: 3} m_Name: m_EditorClassIdentifier: + _pointUtilitiesSO: {fileID: 11400000, guid: 5e210d04f3c81dc4986b2270af79835f, type: 2} _source: {fileID: 9210621271187283363} --- !u!1 &9210621271227589044 GameObject: diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab index 87555dcd..cc251f6b 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16.prefab @@ -152,6 +152,7 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: f2ac6256eabda88478ca2a2fc51a2c64, type: 3} m_Name: m_EditorClassIdentifier: + _pointUtilitiesSO: {fileID: 11400000, guid: 5e210d04f3c81dc4986b2270af79835f, type: 2} _source: {fileID: 5955675792109571644} --- !u!1 &5955675793193326067 GameObject: diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab index 422008b6..b55f166f 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-16HiRes.prefab @@ -304,6 +304,7 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: f2ac6256eabda88478ca2a2fc51a2c64, type: 3} m_Name: m_EditorClassIdentifier: + _pointUtilitiesSO: {fileID: 11400000, guid: 5e210d04f3c81dc4986b2270af79835f, type: 2} _source: {fileID: 5738741472997638426} --- !u!1 &5738741473100887785 GameObject: diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab index 3395904d..018aca19 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLP-32.prefab @@ -67,6 +67,7 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: f2ac6256eabda88478ca2a2fc51a2c64, type: 3} m_Name: m_EditorClassIdentifier: + _pointUtilitiesSO: {fileID: 11400000, guid: 5e210d04f3c81dc4986b2270af79835f, type: 2} _source: {fileID: 4239717977722247697} --- !u!1 &4239717977887452642 GameObject: diff --git a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab index c3fb9a4d..af237e2e 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/LiDAR/Velodyne/VLS-128_with_DepthBuffer.prefab @@ -153,6 +153,7 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: f2ac6256eabda88478ca2a2fc51a2c64, type: 3} m_Name: m_EditorClassIdentifier: + _pointUtilitiesSO: {fileID: 11400000, guid: 5e210d04f3c81dc4986b2270af79835f, type: 2} _source: {fileID: 9219009776518534082} --- !u!1 &9219009777597040757 GameObject: diff --git a/Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset b/Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset new file mode 100644 index 00000000..1e301596 --- /dev/null +++ b/Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset @@ -0,0 +1,20 @@ +%YAML 1.1 +%TAG !u! tag:unity3d.com,2011: +--- !u!114 &11400000 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 0} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: b5c47f036001d1040be206ca55838d54, type: 3} + m_Name: PointUtilitiesSO + m_EditorClassIdentifier: + _pointCloudXYZMaterial: {fileID: 2100000, guid: 7b5638bccb8c4de4b81e565745074a5d, + type: 2} + _pointCloudXYZIMaterial: {fileID: 2100000, guid: ef4427209cbbb224f85dbf16125fc9b5, + type: 2} + _pointCloudXYZRGBMaterial: {fileID: 2100000, guid: abdb03da013965d499191c3affaaa288, + type: 2} diff --git a/Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset.meta b/Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset.meta new file mode 100644 index 00000000..6679a065 --- /dev/null +++ b/Assets/UnitySensors/Runtime/ScriptableObjects/PointUtilitiesSO.asset.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: 5e210d04f3c81dc4986b2270af79835f +NativeFormatImporter: + externalObjects: {} + mainObjectFileID: 11400000 + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Scripts/DataType/Geometry/Vector3D.cs b/Assets/UnitySensors/Runtime/Scripts/DataType/Geometry/Vector3D.cs index 51487ef3..65e5a096 100644 --- a/Assets/UnitySensors/Runtime/Scripts/DataType/Geometry/Vector3D.cs +++ b/Assets/UnitySensors/Runtime/Scripts/DataType/Geometry/Vector3D.cs @@ -1,5 +1,3 @@ -using System.Collections; -using System.Collections.Generic; using UnityEngine; namespace UnitySensors.DataType.Geometry diff --git a/Assets/UnitySensors/Runtime/Scripts/DataType/Sensor/PointCloud/PointXYZRGB.cs b/Assets/UnitySensors/Runtime/Scripts/DataType/Sensor/PointCloud/PointXYZRGB.cs index 0673875e..d735ff4e 100644 --- a/Assets/UnitySensors/Runtime/Scripts/DataType/Sensor/PointCloud/PointXYZRGB.cs +++ b/Assets/UnitySensors/Runtime/Scripts/DataType/Sensor/PointCloud/PointXYZRGB.cs @@ -1,5 +1,3 @@ -using System; -using Unity.Collections; using Unity.Mathematics; using UnitySensors.Interface.Sensor.PointCloud; diff --git a/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/IImuDataInterface.cs b/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/IImuDataInterface.cs index 88a64af2..b590c24e 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/IImuDataInterface.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/IImuDataInterface.cs @@ -1,5 +1,3 @@ -using System.Collections; -using System.Collections.Generic; using UnityEngine; namespace UnitySensors.Interface.Sensor diff --git a/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/PointCloud/IPointInterface.cs b/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/PointCloud/IPointInterface.cs index 55918a8c..654f7fc1 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/PointCloud/IPointInterface.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Interfaces/Sensor/PointCloud/IPointInterface.cs @@ -1,4 +1,3 @@ -using Unity.Collections; using Unity.Mathematics; namespace UnitySensors.Interface.Sensor.PointCloud diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs index b3b93986..baace630 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs @@ -1,5 +1,4 @@ using UnityEngine; -using UnityEngine.Rendering; using UnitySensors.Interface.Sensor; diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/Geometry/GeoCoordinateConverter.cs b/Assets/UnitySensors/Runtime/Scripts/Utils/Geometry/GeoCoordinateConverter.cs index d3a20861..cd122994 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Utils/Geometry/GeoCoordinateConverter.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Utils/Geometry/GeoCoordinateConverter.cs @@ -1,19 +1,18 @@ using System; -using UnityEngine; using UnitySensors.DataType.Geometry; namespace UnitySensors.Utils.Geometry { /// - /// •½–Ê’¼ŠpÀ•WŒn‚ƈܓxŒo“x‚Ì‘ŠŒÝ•ÏŠ· - /// ŽQÆF‘“y’n—‰@‚Ìu‘ª—ÊŒvŽZƒTƒCƒgv + /// ���ʒ��p���W�n�ƈܓx�o�x�̑��ݕϊ� + /// �Q�ÆF���y�n���@�Ìu���ʌv�Z�T�C�g�v /// http://vldb.gsi.go.jp/sokuchi/surveycalc/main.html /// public class GeoCoordinateConverter { - const double daa = 6378137; //’·”¼Œa - const double dF = 298.257222101d; //‹tG•½—¦ - const double dM0 = 0.9999; //•½–Ê’¼ŠpÀ•WŒn‚ÌYŽ²ã‚É‚¨‚¯‚ékŽÚŒW”(UTMÀ•WŒn‚Ìꇨ0.9996) + const double daa = 6378137; //�����a + const double dF = 298.257222101d; //�t�G���� + const double dM0 = 0.9999; //���ʒ��p���W�n��Y����ɂ�����k�ڌW��(UTM���W�n�Ìê‡ï¿½ï¿½0.9996) private GeoCoordinate _origin; @@ -26,7 +25,7 @@ public Vector3D Convert(GeoCoordinate coordinate) { double dn = 1d / (2 * dF - 1); - //ƒ‰ƒWƒAƒ“’PˆÊ‚É + //���W�A���P�ʂ� double Lat = Deg2Rad(coordinate.latitude); double Lon = Deg2Rad(coordinate.longitude); double Lat0 = Deg2Rad(_origin.latitude); @@ -39,7 +38,7 @@ public Vector3D Convert(GeoCoordinate coordinate) double dXi = Math.Atan(dt / dLmc); double dEt = Atanh(dLms / dtb); - //ƒ¿1¨0`ƒ¿5¨4 + //��1��0�`��5��4 double[] dal = new double[6]; dal[0] = 0; dal[1] = 1d / 2d * dn - 2d / 3d * Math.Pow(dn, 2) + 5d / 16d * Math.Pow(dn, 3) + 41d / 180d * Math.Pow(dn, 4) - 127d / 288d * Math.Pow(dn, 5); @@ -85,11 +84,11 @@ public GeoCoordinate Convert(Vector3D coordinate) { double dn = 1d / (2 * dF - 1); - //ƒ‰ƒWƒAƒ“’PˆÊ‚É + //���W�A���P�ʂ� double Lat0 = Deg2Rad(_origin.latitude); double Lon0 = Deg2Rad(_origin.longitude); - //SƒÓ0AA + //S��0�AA double[] dA = new double[6]; dA[0] = 1 + Math.Pow(dn, 2) / 4 + Math.Pow(dn, 4) / 64; dA[1] = -3d / 2d * (dn - Math.Pow(dn, 3) / 8 - Math.Pow(dn, 5) / 64); @@ -105,11 +104,11 @@ public GeoCoordinate Convert(Vector3D coordinate) } dSb = dM0 * daa / (1 + dn) * (dA[0] * Lat0 + dSb); - //ƒÌEƒÅ + //�ÌE�� double dXi = (coordinate.z + dSb) / dAb; double dEt = coordinate.x / dAb; - //ƒÀ + //�� double[] dBt = new double[6]; dBt[1] = 1d / 2d * dn - 2d / 3d * Math.Pow(dn, 2) + 37d / 96d * Math.Pow(dn, 3) - 1d / 360d * Math.Pow(dn, 4) - 81d / 512d * Math.Pow(dn, 5); dBt[2] = 1d / 48d * Math.Pow(dn, 2) + 1d / 15d * Math.Pow(dn, 3) - 437d / 1440d * Math.Pow(dn, 4) + 46d / 105d * Math.Pow(dn, 5); @@ -117,7 +116,7 @@ public GeoCoordinate Convert(Vector3D coordinate) dBt[4] = 4397d / 161280d * Math.Pow(dn, 4) - 11d / 504d * Math.Pow(dn, 5); dBt[5] = 4583d / 161280d * Math.Pow(dn, 5); - //ƒÌfEƒÅ'EƒÐ'EƒÑ'EƒÔ + //�Ìf�E��'�E��'�E��'�E�� double dXi2 = 0; double dEt2 = 0; double dSg2 = 0; @@ -134,7 +133,7 @@ public GeoCoordinate Convert(Vector3D coordinate) dSg2 = 1 - dSg2; double dCi = Math.Asin(Math.Sin(dXi2) / Math.Cosh(dEt2)); - //ƒÂ + //�� double[] dDt = new double[7]; dDt[1] = 2 * dn - 2d / 3d * Math.Pow(dn, 2) - 2 * Math.Pow(dn, 3) + 116d / 45d * Math.Pow(dn, 4) + 26d / 45d * Math.Pow(dn, 5) - 2854d / 675d * Math.Pow(dn, 6); dDt[2] = 7d / 3d * Math.Pow(dn, 2) - 8d / 5d * Math.Pow(dn, 3) - 227d / 45d * Math.Pow(dn, 4) + 2704d / 315d * Math.Pow(dn, 5) + 2323d / 945d * Math.Pow(dn, 6); @@ -143,7 +142,7 @@ public GeoCoordinate Convert(Vector3D coordinate) dDt[5] = 4174d / 315d * Math.Pow(dn, 5) - 144838d / 6237d * Math.Pow(dn, 6); dDt[6] = 601676d / 22275d * Math.Pow(dn, 6); - //ƒ‰ƒWƒAƒ“’PˆÊ‚̈ܓxŒo“x + //���W�A���P�ʂ̈ܓx�o�x double Lat = dCi; double Lon = Lon0 + Math.Atan(Math.Sinh(dEt2) / Math.Cos(dXi2)); for (int j = 1; j <= 6; j++) @@ -153,7 +152,7 @@ public GeoCoordinate Convert(Vector3D coordinate) return new GeoCoordinate(Rad2Deg(Lat), Rad2Deg(Lon), coordinate.y + _origin.altitude); } - //‘o‹Èü³ÚŠÖ”‚Ì‹tŠÖ” + //�o�È����ڊÖ��̋t�Ö� private static double Atanh(double x) => (1d / 2d * Math.Log((1 + x) / (1 - x), Math.E)); private static double Deg2Rad(double Deg) => (Math.PI * Deg / 180d); private static double Rad2Deg(double Rad) => (180d * Rad / Math.PI); diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/Noise/IUpdateGaussianNoisesJob.cs b/Assets/UnitySensors/Runtime/Scripts/Utils/Noise/IUpdateGaussianNoisesJob.cs index 8e4f5a1e..3d19f10c 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Utils/Noise/IUpdateGaussianNoisesJob.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Utils/Noise/IUpdateGaussianNoisesJob.cs @@ -1,5 +1,4 @@ using System; -using UnityEngine; using Unity.Burst; using Unity.Collections; diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs deleted file mode 100644 index 85248b83..00000000 --- a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs +++ /dev/null @@ -1,28 +0,0 @@ -using System; -using System.Collections.Generic; -using System.Collections.ObjectModel; - -using UnitySensors.DataType.Sensor.PointCloud; - -namespace UnitySensors.Utils.PointCloud -{ - // TODO: Rewrite it with scriptable objects - public static class PointUtilities - { - public readonly static ReadOnlyDictionary pointDataSizes = new ReadOnlyDictionary(new Dictionary - { - { typeof(PointXYZ), 12 }, - { typeof(PointXYZI), 16 }, - { typeof(PointXYZRGB), 16 } - }); - - public readonly static ReadOnlyDictionary shaderNames = new ReadOnlyDictionary(new Dictionary - { - // FIXME: Finding shaders by name need to add them to the "Always Included Shaders" list, or they will not work after building. - // Using the material reference would be better. - { typeof(PointXYZ), "UnitySensors/PointCloudXYZ" }, - { typeof(PointXYZI), "UnitySensors/PointCloudXYZI" }, - { typeof(PointXYZRGB), "UnitySensors/PointCloudXYZRGB" } - }); - } -} diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs.meta b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs.meta deleted file mode 100644 index e59c4b4a..00000000 --- a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilities.cs.meta +++ /dev/null @@ -1,11 +0,0 @@ -fileFormatVersion: 2 -guid: 5a30cb1240907864cb62e781c6cdcf3f -MonoImporter: - externalObjects: {} - serializedVersion: 2 - defaultReferences: [] - executionOrder: 0 - icon: {instanceID: 0} - userData: - assetBundleName: - assetBundleVariant: diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs new file mode 100644 index 00000000..352d363a --- /dev/null +++ b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs @@ -0,0 +1,45 @@ + +using System; +using System.Collections.Generic; +using System.Collections.ObjectModel; +using UnityEngine; +using UnitySensors.DataType.Sensor.PointCloud; +namespace UnitySensors.Utils.PointCloud +{ + [CreateAssetMenu(fileName = "PointUtilitiesSO", menuName = "UnitySensors/PointUtilitiesSO", order = 1)] + public class PointUtilitiesSO : ScriptableObject + { + + // TODO: There should be a better way to handle this + [SerializeField] private Material _pointCloudXYZMaterial; + [SerializeField] private Material _pointCloudXYZIMaterial; + [SerializeField] private Material _pointCloudXYZRGBMaterial; + + public readonly static ReadOnlyDictionary pointDataSizes = new ReadOnlyDictionary(new Dictionary + { + { typeof(PointXYZ), 12 }, + { typeof(PointXYZI), 16 }, + { typeof(PointXYZRGB), 16 } + }); + + public Material GetPointMaterialTemplate(Type type) + { + if (type == typeof(PointXYZ)) + { + return _pointCloudXYZMaterial; + } + else if (type == typeof(PointXYZI)) + { + return _pointCloudXYZIMaterial; + } + else if (type == typeof(PointXYZRGB)) + { + return _pointCloudXYZRGBMaterial; + } + else + { + throw new ArgumentException("Unsupported point type"); + } + } + } +} \ No newline at end of file diff --git a/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs.meta b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs.meta new file mode 100644 index 00000000..cc5eee44 --- /dev/null +++ b/Assets/UnitySensors/Runtime/Scripts/Utils/PointCloud/PointUtilitiessSO.cs.meta @@ -0,0 +1,2 @@ +fileFormatVersion: 2 +guid: b5c47f036001d1040be206ca55838d54 \ No newline at end of file diff --git a/Assets/UnitySensors/Runtime/Scripts/Visualizers/Sensor/PointCloudVisualizer.cs b/Assets/UnitySensors/Runtime/Scripts/Visualizers/Sensor/PointCloudVisualizer.cs index 9f25a97f..31da3471 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Visualizers/Sensor/PointCloudVisualizer.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Visualizers/Sensor/PointCloudVisualizer.cs @@ -1,14 +1,13 @@ using UnityEngine; -using UnitySensors.Attribute; using UnitySensors.Interface.Sensor; using UnitySensors.Interface.Sensor.PointCloud; -using UnitySensors.Sensor; using UnitySensors.Utils.PointCloud; namespace UnitySensors.Visualization.Sensor { public class PointCloudVisualizer : Visualizer where T : struct, IPointInterface { + [SerializeField] private PointUtilitiesSO _pointUtilitiesSO; private IPointCloudInterface _sourceInterface; private Transform _transform; @@ -28,9 +27,11 @@ public void SetSource(IPointCloudInterface sourceInterface) protected virtual void Start() { + + _transform = this.transform; - _bufferSize = PointUtilities.pointDataSizes[typeof(T)]; - _mat = new Material(Shader.Find(PointUtilities.shaderNames[typeof(T)])); + _bufferSize = PointUtilitiesSO.pointDataSizes[typeof(T)]; + _mat = new Material(_pointUtilitiesSO.GetPointMaterialTemplate(typeof(T))); _mat.renderQueue = 3000; _mesh = new Mesh(); _mesh.vertices = new Vector3[1] { Vector3.zero }; diff --git a/Assets/UnitySensors/Runtime/Scripts/Visualizers/Visualizer.cs b/Assets/UnitySensors/Runtime/Scripts/Visualizers/Visualizer.cs index bab5d64f..11b2fd67 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Visualizers/Visualizer.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Visualizers/Visualizer.cs @@ -1,6 +1,4 @@ using UnityEngine; -using UnitySensors.Attribute; -using UnitySensors.Sensor; namespace UnitySensors.Visualization { diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs index fae25d77..68708d49 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs @@ -36,7 +36,7 @@ public override void Init() _header.Init(); _pointsNum = _sourceInterface.pointCloud.points.Length; - int sizeOfPoint = PointUtilities.pointDataSizes[typeof(T)]; + int sizeOfPoint = PointUtilitiesSO.pointDataSizes[typeof(T)]; int dataSize = _pointsNum * sizeOfPoint; _msg.height = 1; @@ -60,7 +60,7 @@ public override void Init() public override PointCloud2Msg Serialize() { _msg.header = _header.Serialize(); - + unsafe { UnsafeUtility.MemCpy(NativeArrayUnsafeUtility.GetUnsafePtr(_data), NativeArrayUnsafeUtility.GetUnsafePtr(_sourceInterface.pointCloud.points), _data.Length); @@ -69,7 +69,7 @@ public override PointCloud2Msg Serialize() _jobHandle.Complete(); _data.CopyTo(_msg.data); - + return _msg; } From bbcb79c808bac1498374eec65eb322d9fe37d749 Mon Sep 17 00:00:00 2001 From: chy <1274653465@qq.com> Date: Wed, 20 Nov 2024 00:36:56 +0800 Subject: [PATCH 12/15] Added ImageEncodeJob to speed up Msg encoding; updated Schedule's BatchCount in Job to improve performance; added logging of GPU read errors; removed unsafe code in PointCloud2MsgSerializer. --- .../Camera/DepthCamera/DepthCameraSensor.cs | 4 +- .../Camera/RGBCamera/RGBCameraSensor.cs | 1 + .../Camera/RGBDCamera/RGBDCameraSensor.cs | 6 +- .../DepthBufferLiDARSensor.cs | 5 +- .../LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs | 6 +- .../Prefabs/Camera/DepthCamera_ros.prefab | 7 +- .../SensorMsgs/ImageMsgSerializer.cs | 128 ++++++++---------- .../SensorMsgs/PointCloud2MsgSerializer.cs | 8 +- .../Runtime/Scripts/Utils/Image.meta | 8 ++ .../Scripts/Utils/Image/IImageEncodeJobs.cs | 78 +++++++++++ .../Utils/Image/IImageEncodeJobs.cs.meta | 2 + .../Runtime/UnitySensorsROSRuntime.asmdef | 2 +- 12 files changed, 163 insertions(+), 92 deletions(-) create mode 100644 Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta create mode 100644 Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs create mode 100644 Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs.meta diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs index b6d4cdd7..0bc18cee 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs @@ -113,8 +113,8 @@ protected override void UpdateSensor() { if (!LoadTexture()) return; - JobHandle updateGaussianNoisesJobHandle = _updateGaussianNoisesJob.Schedule(_pointsNum, 1); - _jobHandle = _textureToPointsJob.Schedule(_pointsNum, 1, updateGaussianNoisesJobHandle); + JobHandle updateGaussianNoisesJobHandle = _updateGaussianNoisesJob.Schedule(_pointsNum, 1024); + _jobHandle = _textureToPointsJob.Schedule(_pointsNum, 1024, updateGaussianNoisesJobHandle); JobHandle.ScheduleBatchedJobs(); _jobHandle.Complete(); diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs index 1032012d..26011262 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs @@ -43,6 +43,7 @@ protected bool LoadTexture() { if (request.hasError) { + Debug.LogError("GPU readback error detected."); } else { diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs index 36e86d63..d94ad85d 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBDCamera/RGBDCameraSensor.cs @@ -130,8 +130,8 @@ protected override void UpdateSensor() { if (!LoadDepthTexture() || !LoadColorTexture()) return; - JobHandle updateGaussianNoisesJobHandle = _updateGaussianNoisesJob.Schedule(_pointsNum, 1); - _jobHandle = _textureToPointsJob.Schedule(_pointsNum, 1, updateGaussianNoisesJobHandle); + JobHandle updateGaussianNoisesJobHandle = _updateGaussianNoisesJob.Schedule(_pointsNum, 1024); + _jobHandle = _textureToPointsJob.Schedule(_pointsNum, 1024, updateGaussianNoisesJobHandle); JobHandle.ScheduleBatchedJobs(); _jobHandle.Complete(); @@ -146,6 +146,7 @@ private bool LoadDepthTexture() { if (request.hasError) { + Debug.LogError("GPU readback error detected."); } else { @@ -166,6 +167,7 @@ private bool LoadColorTexture() { if (request.hasError) { + Debug.LogError("GPU readback error detected."); } else { diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs index 440d4787..46092a91 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/DepthBufferLiDAR/DepthBufferLiDARSensor.cs @@ -147,8 +147,8 @@ protected override void UpdateSensor() { if (!LoadTexture()) return; - JobHandle updateGaussianNoisesJobHandle = _updateGaussianNoisesJob.Schedule(pointsNum, 1); - _jobHandle = _textureToPointsJob.Schedule(pointsNum, 1, updateGaussianNoisesJobHandle); + JobHandle updateGaussianNoisesJobHandle = _updateGaussianNoisesJob.Schedule(pointsNum, 1024); + _jobHandle = _textureToPointsJob.Schedule(pointsNum, 1024, updateGaussianNoisesJobHandle); JobHandle.ScheduleBatchedJobs(); _jobHandle.Complete(); @@ -166,6 +166,7 @@ private bool LoadTexture() { if (request.hasError) { + Debug.LogError("GPU readback error detected."); } else { diff --git a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs index ca9cf84d..eee45f04 100644 --- a/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs +++ b/Assets/UnitySensors/Runtime/Scripts/Sensors/LiDAR/RaycastLiDAR/RaycastLiDARSensor.cs @@ -91,10 +91,10 @@ protected override void UpdateSensor() _updateRaycastCommandsJob.origin = _transform.position; _updateRaycastCommandsJob.localToWorldMatrix = _transform.localToWorldMatrix; - JobHandle updateRaycastCommandsJobHandle = _updateRaycastCommandsJob.Schedule(pointsNum, 1); + JobHandle updateRaycastCommandsJobHandle = _updateRaycastCommandsJob.Schedule(pointsNum, 1024); JobHandle updateGaussianNoisesJobHandle = _updateGaussianNoisesJob.Schedule(pointsNum, 1, updateRaycastCommandsJobHandle); - JobHandle raycastJobHandle = RaycastCommand.ScheduleBatch(_raycastCommands, _raycastHits, 256, updateGaussianNoisesJobHandle); - _jobHandle = _raycastHitsToPointsJob.Schedule(pointsNum, 1, raycastJobHandle); + JobHandle raycastJobHandle = RaycastCommand.ScheduleBatch(_raycastCommands, _raycastHits, 1024, updateGaussianNoisesJobHandle); + _jobHandle = _raycastHitsToPointsJob.Schedule(pointsNum, 1024, raycastJobHandle); JobHandle.ScheduleBatchedJobs(); _jobHandle.Complete(); diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab index 70efb7b2..7516a0b4 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/DepthCamera_ros.prefab @@ -125,7 +125,7 @@ MonoBehaviour: _source: {fileID: 4853532333615571030} _header: _source: {fileID: 4853532333615571030} - _frame_id: /camera_frame + _frame_id: camera_frame --- !u!114 &9201004833233192004 MonoBehaviour: m_ObjectHideFlags: 0 @@ -143,7 +143,7 @@ MonoBehaviour: _serializer: _header: _source: {fileID: 4853532333615571030} - _frame_id: /camera_frame + _frame_id: camera_frame _source: {fileID: 4853532333615571030} --- !u!114 &7171801529083048031 MonoBehaviour: @@ -165,4 +165,5 @@ MonoBehaviour: _encoding: 2 _header: _source: {fileID: 4853532333615571030} - _frame_id: /camera_frame + _frame_id: camera_frame + _encodedTexture: {fileID: 0} diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs index ccdf7841..9a636410 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs @@ -5,6 +5,9 @@ using UnitySensors.Attribute; using UnitySensors.Interface.Sensor; using UnitySensors.ROS.Serializer.Std; +using UnitySensors.ROS.Utils.Image; +using Unity.Jobs; +using Unity.Collections; namespace UnitySensors.ROS.Serializer.Sensor { @@ -16,26 +19,6 @@ private enum SourceTexture Texture0, Texture1 } - private enum Encoding - { - _RGB8, - _32FC1, - _16UC1 - } - private struct ColorRGB24 - { - public byte r; - public byte g; - public byte b; - } - private struct Color32FC1 - { - public float r; - } - private struct Color16UC1 - { - public ushort r; - } [SerializeField, Interface(typeof(ITextureInterface))] private Object _source; @@ -43,18 +26,15 @@ private struct Color16UC1 private SourceTexture _sourceTexture; [SerializeField] private Encoding _encoding; + [SerializeField, Attribute.ReadOnly] + private Texture2D _encodedTexture; [SerializeField] private HeaderSerializer _header; private ITextureInterface _sourceInterface; - private Texture2D _flippedTexture; - private float distanceFactor; + private ImageEncodeJob _imageEncodeJob; - private Color[] _sourcePixels; - private ColorRGB24[] _targetPixelsRGB24; - private Color32FC1[] _targetPixels32FC1; - private Color16UC1[] _targetPixels16UC1; public override void Init() { @@ -81,15 +61,31 @@ public override void Init() _msg.encoding = "32FC1"; bytesPerPixel = 1 * 4; textureFormat = TextureFormat.RFloat; - distanceFactor = _sourceInterface.texture0FarClipPlane; - _targetPixels32FC1 = new Color32FC1[width * height]; + float distanceFactor = _sourceInterface.texture0FarClipPlane; + _imageEncodeJob = new() + { + width = width, + height = height, + distanceFactor = distanceFactor, + encoding = _encoding, + targetTexture16UC1 = new NativeArray(0, Allocator.Persistent), + targetTextureRGB8 = new NativeArray(0, Allocator.Persistent) + }; break; case Encoding._16UC1: _msg.encoding = "16UC1"; bytesPerPixel = 1 * 2; textureFormat = TextureFormat.R16; distanceFactor = _sourceInterface.texture0FarClipPlane * 1000; - _targetPixels16UC1 = new Color16UC1[width * height]; + _imageEncodeJob = new() + { + width = width, + height = height, + distanceFactor = distanceFactor, + encoding = _encoding, + targetTexture32FC1 = new NativeArray(0, Allocator.Persistent), + targetTextureRGB8 = new NativeArray(0, Allocator.Persistent) + }; break; case Encoding._RGB8: default: @@ -97,10 +93,17 @@ public override void Init() bytesPerPixel = 3 * 1; textureFormat = TextureFormat.RGB24; distanceFactor = 1; - _targetPixelsRGB24 = new ColorRGB24[width * height]; + _imageEncodeJob = new() + { + width = width, + height = height, + distanceFactor = distanceFactor, + encoding = _encoding, + targetTexture32FC1 = new NativeArray(0, Allocator.Persistent), + targetTexture16UC1 = new NativeArray(0, Allocator.Persistent), + }; break; } - _sourcePixels = new Color[width * height]; _msg.is_bigendian = 0; _msg.width = (uint)width; @@ -108,7 +111,7 @@ public override void Init() _msg.step = (uint)(bytesPerPixel * width); _msg.data = new byte[_msg.step * height]; - _flippedTexture = new Texture2D(width, height, textureFormat, false); + _encodedTexture = new Texture2D(width, height, textureFormat, false); } @@ -117,58 +120,37 @@ public override ImageMsg Serialize() _msg.header = _header.Serialize(); var texture = _sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1; - FlipTextureVertically(texture, _flippedTexture); - - // Manually copy the data to the message to avoid GC allocation - _flippedTexture.GetRawTextureData().CopyTo(_msg.data); - return _msg; - } - private void FlipTextureVertically(Texture2D sourceTexture, Texture2D targetTexture) - { - // TODO: Use shader or jobs to flip the texture - int width = sourceTexture.width; - int height = sourceTexture.height; - - // Manually copy the data to the message to avoid GC allocation - sourceTexture.GetPixelData(0).CopyTo(_sourcePixels); + _imageEncodeJob.sourceTextureRawData = texture.GetRawTextureData(); switch (_encoding) { case Encoding._32FC1: - for (int j = 0; j < height; j++) - { - for (int i = 0; i < width; i++) - { - _targetPixels32FC1[j * width + i].r = _sourcePixels[(height - j - 1) * width + i].r * distanceFactor; - } - } - targetTexture.SetPixelData(_targetPixels32FC1, 0); + _imageEncodeJob.targetTexture32FC1 = _encodedTexture.GetRawTextureData(); break; case Encoding._16UC1: - for (int j = 0; j < height; j++) - { - for (int i = 0; i < width; i++) - { - _targetPixels16UC1[j * width + i].r = (ushort)(_sourcePixels[(height - j - 1) * width + i].r * distanceFactor); - } - } - targetTexture.SetPixelData(_targetPixels16UC1, 0); + _imageEncodeJob.targetTexture16UC1 = _encodedTexture.GetRawTextureData(); break; case Encoding._RGB8: default: - for (int j = 0; j < height; j++) - { - for (int i = 0; i < width; i++) - { - _targetPixelsRGB24[j * width + i].r = (byte)(_sourcePixels[(height - j - 1) * width + i].r * 255); - _targetPixelsRGB24[j * width + i].g = (byte)(_sourcePixels[(height - j - 1) * width + i].g * 255); - _targetPixelsRGB24[j * width + i].b = (byte)(_sourcePixels[(height - j - 1) * width + i].b * 255); - } - } - targetTexture.SetPixelData(_targetPixelsRGB24, 0); + _imageEncodeJob.targetTextureRGB8 = _encodedTexture.GetRawTextureData(); break; } - targetTexture.Apply(); + + _imageEncodeJob.Schedule(texture.width * texture.height, 1024).Complete(); + + _encodedTexture.Apply(); + + // Manually copy the data to the message to avoid GC allocation + _encodedTexture.GetRawTextureData().CopyTo(_msg.data); + return _msg; + } + + public override void OnDestroy() + { + base.OnDestroy(); + _imageEncodeJob.targetTexture32FC1.Dispose(); + _imageEncodeJob.targetTexture16UC1.Dispose(); + _imageEncodeJob.targetTextureRGB8.Dispose(); } } } diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs index 68708d49..fda9be6a 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/PointCloud2MsgSerializer.cs @@ -1,6 +1,5 @@ using UnityEngine; using Unity.Collections; -using Unity.Collections.LowLevel.Unsafe; using Unity.Jobs; using RosMessageTypes.Sensor; @@ -61,11 +60,8 @@ public override PointCloud2Msg Serialize() { _msg.header = _header.Serialize(); - unsafe - { - UnsafeUtility.MemCpy(NativeArrayUnsafeUtility.GetUnsafePtr(_data), NativeArrayUnsafeUtility.GetUnsafePtr(_sourceInterface.pointCloud.points), _data.Length); - } - _jobHandle = _invertXJob.Schedule(_pointsNum, 1); + _sourceInterface.pointCloud.points.Reinterpret(PointUtilitiesSO.pointDataSizes[typeof(T)]).CopyTo(_data); + _jobHandle = _invertXJob.Schedule(_pointsNum, 1024); _jobHandle.Complete(); _data.CopyTo(_msg.data); diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta b/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta new file mode 100644 index 00000000..4f99bcc5 --- /dev/null +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta @@ -0,0 +1,8 @@ +fileFormatVersion: 2 +guid: 2b9ccca7b8586b04fa6457768c935ac0 +folderAsset: yes +DefaultImporter: + externalObjects: {} + userData: + assetBundleName: + assetBundleVariant: diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs new file mode 100644 index 00000000..d4eaa0b8 --- /dev/null +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs @@ -0,0 +1,78 @@ + +using Unity.Burst; +using Unity.Collections; +using Unity.Jobs; +using UnityEngine; + +namespace UnitySensors.ROS.Utils.Image +{ + [BurstCompile] + struct ImageEncodeJob : IJobParallelFor + { + [ReadOnly] + public NativeArray sourceTextureRawData; + [WriteOnly] + public NativeArray targetTextureRGB8; + [WriteOnly] + public NativeArray targetTexture32FC1; + [WriteOnly] + public NativeArray targetTexture16UC1; + [ReadOnly] + public int width; + [ReadOnly] + public int height; + [ReadOnly] + public float distanceFactor; + [ReadOnly] + public Encoding encoding; + public void Execute(int index) + { + int i = index % width; + int j = index / width; + + var sourceColor = sourceTextureRawData[(height - j - 1) * width + i]; + + switch (encoding) + { + case Encoding._32FC1: + var targetColor32FC1 = new Color32FC1(); + targetColor32FC1.r = sourceColor.r * distanceFactor; + targetTexture32FC1[index] = targetColor32FC1; + break; + case Encoding._16UC1: + var targetColor16UC1 = new Color16UC1(); + targetColor16UC1.r = (ushort)(sourceColor.r * distanceFactor); + targetTexture16UC1[index] = targetColor16UC1; + break; + case Encoding._RGB8: + default: + var targetColorRGB8 = new ColorRGB8(); + targetColorRGB8.r = (byte)(sourceColor.r * 255); + targetColorRGB8.g = (byte)(sourceColor.g * 255); + targetColorRGB8.b = (byte)(sourceColor.b * 255); + targetTextureRGB8[index] = targetColorRGB8; + break; + } + } + } + struct Color32FC1 + { + public float r; + } + struct Color16UC1 + { + public ushort r; + } + struct ColorRGB8 + { + public byte r; + public byte g; + public byte b; + } + enum Encoding + { + _RGB8, + _32FC1, + _16UC1 + } +} \ No newline at end of file diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs.meta b/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs.meta new file mode 100644 index 00000000..a2ad74b2 --- /dev/null +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs.meta @@ -0,0 +1,2 @@ +fileFormatVersion: 2 +guid: 4374006d20c280c47969bfebc6ec04c5 \ No newline at end of file diff --git a/Assets/UnitySensorsROS/Runtime/UnitySensorsROSRuntime.asmdef b/Assets/UnitySensorsROS/Runtime/UnitySensorsROSRuntime.asmdef index a6c55a8a..addb9f16 100644 --- a/Assets/UnitySensorsROS/Runtime/UnitySensorsROSRuntime.asmdef +++ b/Assets/UnitySensorsROS/Runtime/UnitySensorsROSRuntime.asmdef @@ -11,7 +11,7 @@ ], "includePlatforms": [], "excludePlatforms": [], - "allowUnsafeCode": true, + "allowUnsafeCode": false, "overrideReferences": false, "precompiledReferences": [], "autoReferenced": true, From eb29f5af5434cd577814a3ac201133f9845529e3 Mon Sep 17 00:00:00 2001 From: DESKTOP-E4VIK7O <1274653465@qq.com> Date: Wed, 20 Nov 2024 15:21:30 +0800 Subject: [PATCH 13/15] Refactored imageEncodeJob to update namespaces and merge target texture data into a single array; disabled HUD display for ROS TCP Connector to avoid lag caused by frequent GC at high frame rates; removed redundant AlwaysIncludedShaders --- Assets/Resources/ROSConnectionPrefab.prefab | 4 +- .../SensorMsgs}/IImageEncodeJobs.cs | 17 ++-- .../SensorMsgs}/IImageEncodeJobs.cs.meta | 0 .../SensorMsgs/ImageMsgSerializer.cs | 96 ++++++------------- .../Runtime/Scripts/Utils/Image.meta | 8 -- ProjectSettings/GraphicsSettings.asset | 3 - 6 files changed, 38 insertions(+), 90 deletions(-) rename Assets/UnitySensorsROS/Runtime/Scripts/{Utils/Image => Serializers/SensorMsgs}/IImageEncodeJobs.cs (79%) rename Assets/UnitySensorsROS/Runtime/Scripts/{Utils/Image => Serializers/SensorMsgs}/IImageEncodeJobs.cs.meta (100%) delete mode 100644 Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta diff --git a/Assets/Resources/ROSConnectionPrefab.prefab b/Assets/Resources/ROSConnectionPrefab.prefab index aa3e72f4..b8128ce3 100644 --- a/Assets/Resources/ROSConnectionPrefab.prefab +++ b/Assets/Resources/ROSConnectionPrefab.prefab @@ -24,13 +24,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 5759000335426716240} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &8497029536680012343 MonoBehaviour: @@ -50,7 +50,7 @@ MonoBehaviour: m_KeepaliveTime: 1 m_NetworkTimeoutSeconds: 2 m_SleepTimeSeconds: 0.01 - m_ShowHUD: 1 + m_ShowHUD: 0 m_TFTopics: - /tf listenForTFMessages: 1 diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/IImageEncodeJobs.cs similarity index 79% rename from Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs rename to Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/IImageEncodeJobs.cs index d4eaa0b8..60c61408 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/IImageEncodeJobs.cs @@ -4,7 +4,7 @@ using Unity.Jobs; using UnityEngine; -namespace UnitySensors.ROS.Utils.Image +namespace UnitySensors.ROS.Serializer.Image { [BurstCompile] struct ImageEncodeJob : IJobParallelFor @@ -12,11 +12,7 @@ struct ImageEncodeJob : IJobParallelFor [ReadOnly] public NativeArray sourceTextureRawData; [WriteOnly] - public NativeArray targetTextureRGB8; - [WriteOnly] - public NativeArray targetTexture32FC1; - [WriteOnly] - public NativeArray targetTexture16UC1; + public NativeArray targetTextureRawData; [ReadOnly] public int width; [ReadOnly] @@ -25,10 +21,13 @@ struct ImageEncodeJob : IJobParallelFor public float distanceFactor; [ReadOnly] public Encoding encoding; + [ReadOnly] + public int bytesPerPixel; public void Execute(int index) { int i = index % width; int j = index / width; + int targetIndex = index * bytesPerPixel; var sourceColor = sourceTextureRawData[(height - j - 1) * width + i]; @@ -37,12 +36,12 @@ public void Execute(int index) case Encoding._32FC1: var targetColor32FC1 = new Color32FC1(); targetColor32FC1.r = sourceColor.r * distanceFactor; - targetTexture32FC1[index] = targetColor32FC1; + targetTextureRawData.ReinterpretStore(targetIndex, targetColor32FC1); break; case Encoding._16UC1: var targetColor16UC1 = new Color16UC1(); targetColor16UC1.r = (ushort)(sourceColor.r * distanceFactor); - targetTexture16UC1[index] = targetColor16UC1; + targetTextureRawData.ReinterpretStore(targetIndex, targetColor16UC1); break; case Encoding._RGB8: default: @@ -50,7 +49,7 @@ public void Execute(int index) targetColorRGB8.r = (byte)(sourceColor.r * 255); targetColorRGB8.g = (byte)(sourceColor.g * 255); targetColorRGB8.b = (byte)(sourceColor.b * 255); - targetTextureRGB8[index] = targetColorRGB8; + targetTextureRawData.ReinterpretStore(targetIndex, targetColorRGB8); break; } } diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs.meta b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/IImageEncodeJobs.cs.meta similarity index 100% rename from Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image/IImageEncodeJobs.cs.meta rename to Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/IImageEncodeJobs.cs.meta diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs index 9a636410..afef98e9 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/SensorMsgs/ImageMsgSerializer.cs @@ -1,3 +1,4 @@ +using Unity.Jobs; using UnityEngine; using RosMessageTypes.Sensor; @@ -5,9 +6,7 @@ using UnitySensors.Attribute; using UnitySensors.Interface.Sensor; using UnitySensors.ROS.Serializer.Std; -using UnitySensors.ROS.Utils.Image; -using Unity.Jobs; -using Unity.Collections; +using UnitySensors.ROS.Serializer.Image; namespace UnitySensors.ROS.Serializer.Sensor { @@ -26,12 +25,13 @@ private enum SourceTexture private SourceTexture _sourceTexture; [SerializeField] private Encoding _encoding; - [SerializeField, Attribute.ReadOnly] + [SerializeField, ReadOnly] private Texture2D _encodedTexture; [SerializeField] private HeaderSerializer _header; - + private int _width; + private int _height; private ITextureInterface _sourceInterface; private ImageEncodeJob _imageEncodeJob; @@ -50,93 +50,61 @@ public override void Init() return; } - int width = texture.width; - int height = texture.height; + _width = texture.width; + _height = texture.height; uint bytesPerPixel; TextureFormat textureFormat; + + _imageEncodeJob = new() + { + width = _width, + height = _height, + encoding = _encoding, + sourceTextureRawData = texture.GetRawTextureData(), + }; + switch (_encoding) { case Encoding._32FC1: _msg.encoding = "32FC1"; bytesPerPixel = 1 * 4; textureFormat = TextureFormat.RFloat; - float distanceFactor = _sourceInterface.texture0FarClipPlane; - _imageEncodeJob = new() - { - width = width, - height = height, - distanceFactor = distanceFactor, - encoding = _encoding, - targetTexture16UC1 = new NativeArray(0, Allocator.Persistent), - targetTextureRGB8 = new NativeArray(0, Allocator.Persistent) - }; + _imageEncodeJob.distanceFactor = _sourceInterface.texture0FarClipPlane; + break; case Encoding._16UC1: _msg.encoding = "16UC1"; bytesPerPixel = 1 * 2; textureFormat = TextureFormat.R16; - distanceFactor = _sourceInterface.texture0FarClipPlane * 1000; - _imageEncodeJob = new() - { - width = width, - height = height, - distanceFactor = distanceFactor, - encoding = _encoding, - targetTexture32FC1 = new NativeArray(0, Allocator.Persistent), - targetTextureRGB8 = new NativeArray(0, Allocator.Persistent) - }; + _imageEncodeJob.distanceFactor = _sourceInterface.texture0FarClipPlane * 1000; break; case Encoding._RGB8: default: _msg.encoding = "rgb8"; bytesPerPixel = 3 * 1; textureFormat = TextureFormat.RGB24; - distanceFactor = 1; - _imageEncodeJob = new() - { - width = width, - height = height, - distanceFactor = distanceFactor, - encoding = _encoding, - targetTexture32FC1 = new NativeArray(0, Allocator.Persistent), - targetTexture16UC1 = new NativeArray(0, Allocator.Persistent), - }; + _imageEncodeJob.distanceFactor = 1; break; } _msg.is_bigendian = 0; - _msg.width = (uint)width; - _msg.height = (uint)height; - _msg.step = (uint)(bytesPerPixel * width); - _msg.data = new byte[_msg.step * height]; + _msg.width = (uint)_width; + _msg.height = (uint)_height; + _msg.step = (uint)(bytesPerPixel * _width); + _msg.data = new byte[_msg.step * _height]; - _encodedTexture = new Texture2D(width, height, textureFormat, false); + _imageEncodeJob.bytesPerPixel = (int)bytesPerPixel; + _encodedTexture = new Texture2D(_width, _height, textureFormat, false); } public override ImageMsg Serialize() { _msg.header = _header.Serialize(); - var texture = _sourceTexture == SourceTexture.Texture0 ? _sourceInterface.texture0 : _sourceInterface.texture1; - _imageEncodeJob.sourceTextureRawData = texture.GetRawTextureData(); - - switch (_encoding) - { - case Encoding._32FC1: - _imageEncodeJob.targetTexture32FC1 = _encodedTexture.GetRawTextureData(); - break; - case Encoding._16UC1: - _imageEncodeJob.targetTexture16UC1 = _encodedTexture.GetRawTextureData(); - break; - case Encoding._RGB8: - default: - _imageEncodeJob.targetTextureRGB8 = _encodedTexture.GetRawTextureData(); - break; - } - - _imageEncodeJob.Schedule(texture.width * texture.height, 1024).Complete(); + _imageEncodeJob.targetTextureRawData = _encodedTexture.GetRawTextureData(); + _imageEncodeJob.Schedule(_width * _height, 1024).Complete(); _encodedTexture.Apply(); @@ -144,13 +112,5 @@ public override ImageMsg Serialize() _encodedTexture.GetRawTextureData().CopyTo(_msg.data); return _msg; } - - public override void OnDestroy() - { - base.OnDestroy(); - _imageEncodeJob.targetTexture32FC1.Dispose(); - _imageEncodeJob.targetTexture16UC1.Dispose(); - _imageEncodeJob.targetTextureRGB8.Dispose(); - } } } diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta b/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta deleted file mode 100644 index 4f99bcc5..00000000 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Utils/Image.meta +++ /dev/null @@ -1,8 +0,0 @@ -fileFormatVersion: 2 -guid: 2b9ccca7b8586b04fa6457768c935ac0 -folderAsset: yes -DefaultImporter: - externalObjects: {} - userData: - assetBundleName: - assetBundleVariant: diff --git a/ProjectSettings/GraphicsSettings.asset b/ProjectSettings/GraphicsSettings.asset index e1275984..ad090e32 100644 --- a/ProjectSettings/GraphicsSettings.asset +++ b/ProjectSettings/GraphicsSettings.asset @@ -33,9 +33,6 @@ GraphicsSettings: - {fileID: 15106, guid: 0000000000000000f000000000000000, type: 0} - {fileID: 10753, guid: 0000000000000000f000000000000000, type: 0} - {fileID: 10770, guid: 0000000000000000f000000000000000, type: 0} - - {fileID: 4800000, guid: 0faabdfb36dc37944bd5237eb87dff3e, type: 3} - - {fileID: 4800000, guid: f9fa29512657a5b408ef0c50698b141b, type: 3} - - {fileID: 4800000, guid: 417e6f59011b2b743a51b9344a78b15d, type: 3} m_PreloadedShaders: [] m_PreloadShadersBatchTimeLimit: -1 m_SpritesDefaultMaterial: {fileID: 10754, guid: 0000000000000000f000000000000000, From a2b6711d7f743b7e379b130a57cfb3ee047b0250 Mon Sep 17 00:00:00 2001 From: DESKTOP-E4VIK7O <1274653465@qq.com> Date: Wed, 20 Nov 2024 19:37:47 +0800 Subject: [PATCH 14/15] Updated several prefabs to add PointUtilitiesSO references; fixed camera frame_id format; fixed TFMessageMsgSerializer multiple TransformStampedMsg references to the same HeaderMsg --- .../Runtime/Prefabs/Camera/DepthCamera.prefab | 1 + .../Runtime/Prefabs/Camera/RGBDCamera.prefab | 17 + .../Samples/Camera/Demo_DepthCamera.unity | 5 - .../Samples/Camera/Demo_RGBDCamera.unity | 377 +++++++++++------- .../Demo_VLS-128_with_DepthBuffer.unity | 5 - .../Prefabs/Camera/RGBCamera_ros.prefab | 4 +- .../Prefabs/Camera/RGBDCamera_ros.prefab | 7 +- .../Runtime/Prefabs/GNSS/GNSS_ros.prefab | 2 +- .../GroundTruth/GroundTruth_ros.prefab | 2 +- .../Runtime/Prefabs/IMU/IMU_ros.prefab | 2 +- .../Tf2Msgs/TFMessageMsgSerializer.cs | 6 +- 11 files changed, 261 insertions(+), 167 deletions(-) diff --git a/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab b/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab index d6286b51..ae3756fd 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/Camera/DepthCamera.prefab @@ -118,6 +118,7 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: f2f05a788e73116488577387bd40affc, type: 3} m_Name: m_EditorClassIdentifier: + _pointUtilitiesSO: {fileID: 11400000, guid: 5e210d04f3c81dc4986b2270af79835f, type: 2} _source: {fileID: 1105687583338018398} --- !u!114 &-1608031838711272521 MonoBehaviour: diff --git a/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab b/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab index f16a1857..c4bade1d 100644 --- a/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab +++ b/Assets/UnitySensors/Runtime/Prefabs/Camera/RGBDCamera.prefab @@ -13,6 +13,7 @@ GameObject: - component: {fileID: 4070371534656761714} - component: {fileID: 4022873546115888586} - component: {fileID: 421189727119020206} + - component: {fileID: 4330187045351998600} m_Layer: 0 m_Name: RGBDCamera m_TagString: Untagged @@ -118,6 +119,7 @@ MonoBehaviour: m_Script: {fileID: 11500000, guid: 1a3dffef534585740aa9f93736bdd5ca, type: 3} m_Name: m_EditorClassIdentifier: + _pointUtilitiesSO: {fileID: 11400000, guid: 5e210d04f3c81dc4986b2270af79835f, type: 2} _source: {fileID: 4070371534656761714} --- !u!114 &421189727119020206 MonoBehaviour: @@ -134,3 +136,18 @@ MonoBehaviour: _source: {fileID: 4070371534656761714} _sourceTexture: 0 _image: {fileID: 0} +--- !u!114 &4330187045351998600 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 1785895639420286579} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 5202acb8ddfd0c546b69f23eb10b4e60, type: 3} + m_Name: + m_EditorClassIdentifier: + _source: {fileID: 4070371534656761714} + _sourceTexture: 1 + _image: {fileID: 0} diff --git a/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity b/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity index 86aebeb7..9498e749 100644 --- a/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity +++ b/Assets/UnitySensors/Samples/Camera/Demo_DepthCamera.unity @@ -794,11 +794,6 @@ PrefabInstance: propertyPath: _maxRange value: 20 objectReference: {fileID: 0} - - target: {fileID: 1105687583338018398, guid: 20f112f7f4e74c84693eb6c82e49358f, - type: 3} - propertyPath: _gaussianNoiseSigma - value: 0.1 - objectReference: {fileID: 0} m_RemovedComponents: [] m_RemovedGameObjects: [] m_AddedGameObjects: [] diff --git a/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity b/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity index cd142350..00e12aaa 100644 --- a/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity +++ b/Assets/UnitySensors/Samples/Camera/Demo_RGBDCamera.unity @@ -119,6 +119,78 @@ NavMeshSettings: debug: m_Flags: 0 m_NavMeshData: {fileID: 0} +--- !u!1 &48307302 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 48307303} + - component: {fileID: 48307305} + - component: {fileID: 48307304} + m_Layer: 5 + m_Name: DepthImage + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!224 &48307303 +RectTransform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 48307302} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 599610424} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} + m_AnchorMin: {x: 0.5, y: 0.5} + m_AnchorMax: {x: 0.5, y: 0.5} + m_AnchoredPosition: {x: 355, y: 0} + m_SizeDelta: {x: 640, y: 480} + m_Pivot: {x: 0.5, y: 0.5} +--- !u!114 &48307304 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 48307302} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 1344c3c82d62a2a41a3576d8abb8e3ea, type: 3} + m_Name: + m_EditorClassIdentifier: + m_Material: {fileID: 0} + m_Color: {r: 1, g: 1, b: 1, a: 1} + m_RaycastTarget: 1 + m_RaycastPadding: {x: 0, y: 0, z: 0, w: 0} + m_Maskable: 1 + m_OnCullStateChanged: + m_PersistentCalls: + m_Calls: [] + m_Texture: {fileID: 0} + m_UVRect: + serializedVersion: 2 + x: 0 + y: 0 + width: 1 + height: 1 +--- !u!222 &48307305 +CanvasRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 48307302} + m_CullTransparentMesh: 1 --- !u!1 &62720512 GameObject: m_ObjectHideFlags: 0 @@ -204,13 +276,85 @@ Transform: m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 62720512} serializedVersion: 2 - m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} - m_LocalPosition: {x: 100, y: 1, z: 0} + m_LocalRotation: {x: -0.38184884, y: 0.0074841874, z: -0.0030918354, w: -0.9241893} + m_LocalPosition: {x: -0.3166046, y: 26.904854, z: -28.90025} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} +--- !u!1 &104780346 +GameObject: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + serializedVersion: 6 + m_Component: + - component: {fileID: 104780347} + - component: {fileID: 104780349} + - component: {fileID: 104780348} + m_Layer: 5 + m_Name: ColorImage + m_TagString: Untagged + m_Icon: {fileID: 0} + m_NavMeshLayer: 0 + m_StaticEditorFlags: 0 + m_IsActive: 1 +--- !u!224 &104780347 +RectTransform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 104780346} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 1, y: 1, z: 1} + m_ConstrainProportionsScale: 0 + m_Children: [] + m_Father: {fileID: 599610424} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} + m_AnchorMin: {x: 0.5, y: 0.5} + m_AnchorMax: {x: 0.5, y: 0.5} + m_AnchoredPosition: {x: -355, y: 0} + m_SizeDelta: {x: 640, y: 480} + m_Pivot: {x: 0.5, y: 0.5} +--- !u!114 &104780348 +MonoBehaviour: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 104780346} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: 1344c3c82d62a2a41a3576d8abb8e3ea, type: 3} + m_Name: + m_EditorClassIdentifier: + m_Material: {fileID: 0} + m_Color: {r: 1, g: 1, b: 1, a: 1} + m_RaycastTarget: 1 + m_RaycastPadding: {x: 0, y: 0, z: 0, w: 0} + m_Maskable: 1 + m_OnCullStateChanged: + m_PersistentCalls: + m_Calls: [] + m_Texture: {fileID: 0} + m_UVRect: + serializedVersion: 2 + x: 0 + y: 0 + width: 1 + height: 1 +--- !u!222 &104780349 +CanvasRenderer: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 104780346} + m_CullTransparentMesh: 1 --- !u!1 &135884633 GameObject: m_ObjectHideFlags: 0 @@ -381,7 +525,7 @@ PrefabInstance: addedObject: {fileID: 666016651} m_AddedComponents: [] m_SourcePrefab: {fileID: 100100000, guid: 581b84ef57339314c92df1cef0a06b47, type: 3} ---- !u!1 &492062520 +--- !u!1 &599610420 GameObject: m_ObjectHideFlags: 0 m_CorrespondingSourceObject: {fileID: 0} @@ -389,70 +533,101 @@ GameObject: m_PrefabAsset: {fileID: 0} serializedVersion: 6 m_Component: - - component: {fileID: 492062521} - - component: {fileID: 492062523} - - component: {fileID: 492062522} + - component: {fileID: 599610424} + - component: {fileID: 599610423} + - component: {fileID: 599610422} + - component: {fileID: 599610421} m_Layer: 5 - m_Name: ColorImage + m_Name: Canvas m_TagString: Untagged m_Icon: {fileID: 0} m_NavMeshLayer: 0 m_StaticEditorFlags: 0 m_IsActive: 1 ---- !u!224 &492062521 -RectTransform: +--- !u!114 &599610421 +MonoBehaviour: m_ObjectHideFlags: 0 m_CorrespondingSourceObject: {fileID: 0} m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} - m_GameObject: {fileID: 492062520} - m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} - m_LocalPosition: {x: 0, y: 0, z: 0} - m_LocalScale: {x: 1, y: 1, z: 1} - m_ConstrainProportionsScale: 0 - m_Children: [] - m_Father: {fileID: 1180426313} - m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} - m_AnchorMin: {x: 0.5, y: 0.5} - m_AnchorMax: {x: 0.5, y: 0.5} - m_AnchoredPosition: {x: 0, y: 0} - m_SizeDelta: {x: 640, y: 480} - m_Pivot: {x: 0.5, y: 0.5} ---- !u!114 &492062522 + m_GameObject: {fileID: 599610420} + m_Enabled: 1 + m_EditorHideFlags: 0 + m_Script: {fileID: 11500000, guid: dc42784cf147c0c48a680349fa168899, type: 3} + m_Name: + m_EditorClassIdentifier: + m_IgnoreReversedGraphics: 1 + m_BlockingObjects: 0 + m_BlockingMask: + serializedVersion: 2 + m_Bits: 4294967295 +--- !u!114 &599610422 MonoBehaviour: m_ObjectHideFlags: 0 m_CorrespondingSourceObject: {fileID: 0} m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} - m_GameObject: {fileID: 492062520} + m_GameObject: {fileID: 599610420} m_Enabled: 1 m_EditorHideFlags: 0 - m_Script: {fileID: 11500000, guid: 1344c3c82d62a2a41a3576d8abb8e3ea, type: 3} + m_Script: {fileID: 11500000, guid: 0cd44c1031e13a943bb63640046fad76, type: 3} m_Name: m_EditorClassIdentifier: - m_Material: {fileID: 0} - m_Color: {r: 1, g: 1, b: 1, a: 1} - m_RaycastTarget: 1 - m_RaycastPadding: {x: 0, y: 0, z: 0, w: 0} - m_Maskable: 1 - m_OnCullStateChanged: - m_PersistentCalls: - m_Calls: [] - m_Texture: {fileID: 0} - m_UVRect: - serializedVersion: 2 - x: 0 - y: 0 - width: 1 - height: 1 ---- !u!222 &492062523 -CanvasRenderer: + m_UiScaleMode: 1 + m_ReferencePixelsPerUnit: 100 + m_ScaleFactor: 1 + m_ReferenceResolution: {x: 1920, y: 1080} + m_ScreenMatchMode: 0 + m_MatchWidthOrHeight: 1 + m_PhysicalUnit: 3 + m_FallbackScreenDPI: 96 + m_DefaultSpriteDPI: 96 + m_DynamicPixelsPerUnit: 1 + m_PresetInfoIsWorld: 0 +--- !u!223 &599610423 +Canvas: m_ObjectHideFlags: 0 m_CorrespondingSourceObject: {fileID: 0} m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} - m_GameObject: {fileID: 492062520} - m_CullTransparentMesh: 1 + m_GameObject: {fileID: 599610420} + m_Enabled: 1 + serializedVersion: 3 + m_RenderMode: 0 + m_Camera: {fileID: 0} + m_PlaneDistance: 100 + m_PixelPerfect: 0 + m_ReceivesEvents: 1 + m_OverrideSorting: 0 + m_OverridePixelPerfect: 0 + m_SortingBucketNormalizedSize: 0 + m_VertexColorAlwaysGammaSpace: 0 + m_AdditionalShaderChannelsFlag: 0 + m_UpdateRectTransformForStandalone: 0 + m_SortingLayerID: 0 + m_SortingOrder: 0 + m_TargetDisplay: 0 +--- !u!224 &599610424 +RectTransform: + m_ObjectHideFlags: 0 + m_CorrespondingSourceObject: {fileID: 0} + m_PrefabInstance: {fileID: 0} + m_PrefabAsset: {fileID: 0} + m_GameObject: {fileID: 599610420} + m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} + m_LocalPosition: {x: 0, y: 0, z: 0} + m_LocalScale: {x: 0, y: 0, z: 0} + m_ConstrainProportionsScale: 0 + m_Children: + - {fileID: 104780347} + - {fileID: 48307303} + m_Father: {fileID: 0} + m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} + m_AnchorMin: {x: 0, y: 0} + m_AnchorMax: {x: 0, y: 0} + m_AnchoredPosition: {x: 0, y: 0} + m_SizeDelta: {x: 0, y: 0} + m_Pivot: {x: 0, y: 0} --- !u!1001 &666016650 PrefabInstance: m_ObjectHideFlags: 0 @@ -461,6 +636,11 @@ PrefabInstance: serializedVersion: 3 m_TransformParent: {fileID: 1454009686} m_Modifications: + - target: {fileID: 421189727119020206, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: _image + value: + objectReference: {fileID: 48307304} - target: {fileID: 1785895639420286472, guid: 6a2c732697fa6da47999dd17b096ab09, type: 3} propertyPath: m_LocalPosition.x @@ -516,6 +696,11 @@ PrefabInstance: propertyPath: m_Name value: RGBDCamera objectReference: {fileID: 0} + - target: {fileID: 4330187045351998600, guid: 6a2c732697fa6da47999dd17b096ab09, + type: 3} + propertyPath: _image + value: + objectReference: {fileID: 104780348} m_RemovedComponents: [] m_RemovedGameObjects: [] m_AddedGameObjects: [] @@ -527,108 +712,6 @@ Transform: type: 3} m_PrefabInstance: {fileID: 666016650} m_PrefabAsset: {fileID: 0} ---- !u!1 &1180426309 -GameObject: - m_ObjectHideFlags: 0 - m_CorrespondingSourceObject: {fileID: 0} - m_PrefabInstance: {fileID: 0} - m_PrefabAsset: {fileID: 0} - serializedVersion: 6 - m_Component: - - component: {fileID: 1180426313} - - component: {fileID: 1180426312} - - component: {fileID: 1180426311} - - component: {fileID: 1180426310} - m_Layer: 5 - m_Name: Canvas - m_TagString: Untagged - m_Icon: {fileID: 0} - m_NavMeshLayer: 0 - m_StaticEditorFlags: 0 - m_IsActive: 1 ---- !u!114 &1180426310 -MonoBehaviour: - m_ObjectHideFlags: 0 - m_CorrespondingSourceObject: {fileID: 0} - m_PrefabInstance: {fileID: 0} - m_PrefabAsset: {fileID: 0} - m_GameObject: {fileID: 1180426309} - m_Enabled: 1 - m_EditorHideFlags: 0 - m_Script: {fileID: 11500000, guid: dc42784cf147c0c48a680349fa168899, type: 3} - m_Name: - m_EditorClassIdentifier: - m_IgnoreReversedGraphics: 1 - m_BlockingObjects: 0 - m_BlockingMask: - serializedVersion: 2 - m_Bits: 4294967295 ---- !u!114 &1180426311 -MonoBehaviour: - m_ObjectHideFlags: 0 - m_CorrespondingSourceObject: {fileID: 0} - m_PrefabInstance: {fileID: 0} - m_PrefabAsset: {fileID: 0} - m_GameObject: {fileID: 1180426309} - m_Enabled: 1 - m_EditorHideFlags: 0 - m_Script: {fileID: 11500000, guid: 0cd44c1031e13a943bb63640046fad76, type: 3} - m_Name: - m_EditorClassIdentifier: - m_UiScaleMode: 1 - m_ReferencePixelsPerUnit: 100 - m_ScaleFactor: 1 - m_ReferenceResolution: {x: 1920, y: 1080} - m_ScreenMatchMode: 0 - m_MatchWidthOrHeight: 1 - m_PhysicalUnit: 3 - m_FallbackScreenDPI: 96 - m_DefaultSpriteDPI: 96 - m_DynamicPixelsPerUnit: 1 - m_PresetInfoIsWorld: 0 ---- !u!223 &1180426312 -Canvas: - m_ObjectHideFlags: 0 - m_CorrespondingSourceObject: {fileID: 0} - m_PrefabInstance: {fileID: 0} - m_PrefabAsset: {fileID: 0} - m_GameObject: {fileID: 1180426309} - m_Enabled: 1 - serializedVersion: 3 - m_RenderMode: 0 - m_Camera: {fileID: 0} - m_PlaneDistance: 100 - m_PixelPerfect: 0 - m_ReceivesEvents: 1 - m_OverrideSorting: 0 - m_OverridePixelPerfect: 0 - m_SortingBucketNormalizedSize: 0 - m_VertexColorAlwaysGammaSpace: 0 - m_AdditionalShaderChannelsFlag: 0 - m_UpdateRectTransformForStandalone: 0 - m_SortingLayerID: 0 - m_SortingOrder: 0 - m_TargetDisplay: 0 ---- !u!224 &1180426313 -RectTransform: - m_ObjectHideFlags: 0 - m_CorrespondingSourceObject: {fileID: 0} - m_PrefabInstance: {fileID: 0} - m_PrefabAsset: {fileID: 0} - m_GameObject: {fileID: 1180426309} - m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} - m_LocalPosition: {x: 0, y: 0, z: 0} - m_LocalScale: {x: 0, y: 0, z: 0} - m_ConstrainProportionsScale: 0 - m_Children: - - {fileID: 492062521} - m_Father: {fileID: 0} - m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} - m_AnchorMin: {x: 0, y: 0} - m_AnchorMax: {x: 0, y: 0} - m_AnchoredPosition: {x: 0, y: 0} - m_SizeDelta: {x: 0, y: 0} - m_Pivot: {x: 0, y: 0} --- !u!4 &1454009686 stripped Transform: m_CorrespondingSourceObject: {fileID: 2848956544552890604, guid: 581b84ef57339314c92df1cef0a06b47, @@ -709,6 +792,6 @@ SceneRoots: m_Roots: - {fileID: 135884635} - {fileID: 189404109} - - {fileID: 1180426313} - {fileID: 1489775041} - {fileID: 62720515} + - {fileID: 599610424} diff --git a/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity b/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity index 9427a851..bab92377 100644 --- a/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity +++ b/Assets/UnitySensors/Samples/LiDAR/Velodyne/Demo_VLS-128_with_DepthBuffer.unity @@ -401,11 +401,6 @@ PrefabInstance: serializedVersion: 3 m_TransformParent: {fileID: 1438717031} m_Modifications: - - target: {fileID: 9107878023928292438, guid: aebab1e4472b99644b8adae9c42cc898, - type: 3} - propertyPath: m_Enabled - value: 0 - objectReference: {fileID: 0} - target: {fileID: 9219009777992118712, guid: aebab1e4472b99644b8adae9c42cc898, type: 3} propertyPath: m_RootOrder diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab index e73bf367..21ebf47f 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBCamera_ros.prefab @@ -119,7 +119,7 @@ MonoBehaviour: _source: {fileID: 2016422477619200576} _header: _source: {fileID: 2016422477619200576} - _frame_id: /camera_frame + _frame_id: camera_frame --- !u!114 &7476313626036288691 MonoBehaviour: m_ObjectHideFlags: 0 @@ -139,5 +139,5 @@ MonoBehaviour: _sourceTexture: 0 _header: _source: {fileID: 2016422477619200576} - _frame_id: /camera_frame + _frame_id: camera_frame quality: 75 diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab index ee9d9115..b398e1ae 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/Camera/RGBDCamera_ros.prefab @@ -126,7 +126,7 @@ MonoBehaviour: _source: {fileID: 6928715047789551323} _header: _source: {fileID: 6928715047789551323} - _frame_id: /camera_frame + _frame_id: camera_frame --- !u!114 &2224187045829796718 MonoBehaviour: m_ObjectHideFlags: 0 @@ -164,9 +164,10 @@ MonoBehaviour: _source: {fileID: 6928715047789551323} _sourceTexture: 0 _encoding: 2 + _encodedTexture: {fileID: 0} _header: _source: {fileID: 6928715047789551323} - _frame_id: /camera_frame + _frame_id: camera_frame --- !u!114 &8736958369943202624 MonoBehaviour: m_ObjectHideFlags: 0 @@ -186,5 +187,5 @@ MonoBehaviour: _sourceTexture: 1 _header: _source: {fileID: 6928715047789551323} - _frame_id: /camera_frame + _frame_id: camera_frame quality: 75 diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/GNSS/GNSS_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/GNSS/GNSS_ros.prefab index 7e26f6a6..94017279 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/GNSS/GNSS_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/GNSS/GNSS_ros.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 3192925013080293980} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &3192925013080293982 MonoBehaviour: diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/GroundTruth/GroundTruth_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/GroundTruth/GroundTruth_ros.prefab index caa14f08..a162cff5 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/GroundTruth/GroundTruth_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/GroundTruth/GroundTruth_ros.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 6638955471370723587} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &2623422876239157573 MonoBehaviour: diff --git a/Assets/UnitySensorsROS/Runtime/Prefabs/IMU/IMU_ros.prefab b/Assets/UnitySensorsROS/Runtime/Prefabs/IMU/IMU_ros.prefab index 1ad7c1b2..499e106e 100644 --- a/Assets/UnitySensorsROS/Runtime/Prefabs/IMU/IMU_ros.prefab +++ b/Assets/UnitySensorsROS/Runtime/Prefabs/IMU/IMU_ros.prefab @@ -25,13 +25,13 @@ Transform: m_PrefabInstance: {fileID: 0} m_PrefabAsset: {fileID: 0} m_GameObject: {fileID: 3526848927119471300} + serializedVersion: 2 m_LocalRotation: {x: 0, y: 0, z: 0, w: 1} m_LocalPosition: {x: 0, y: 0, z: 0} m_LocalScale: {x: 1, y: 1, z: 1} m_ConstrainProportionsScale: 0 m_Children: [] m_Father: {fileID: 0} - m_RootOrder: 0 m_LocalEulerAnglesHint: {x: 0, y: 0, z: 0} --- !u!114 &3526848927119471302 MonoBehaviour: diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs index bc1163c6..e5b199de 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs @@ -33,10 +33,12 @@ public override TFMessageMsg Serialize() List transforms = new List(); TFData[] tfData = _source.GetTFData(); - foreach(TFData data in tfData) + foreach (TFData data in tfData) { TransformStampedMsg transform = new TransformStampedMsg(); - transform.header = headerMsg; + transform.header = new HeaderMsg(); + transform.header.stamp = headerMsg.stamp; + transform.header.seq = headerMsg.seq; transform.header.frame_id = data.frame_id_parent; transform.child_frame_id = data.frame_id_child; transform.transform.translation = data.position.To(); From 58c7e1d487f366c34238106186a612d7dd27742f Mon Sep 17 00:00:00 2001 From: chy <1274653465@qq.com> Date: Wed, 20 Nov 2024 20:25:21 +0800 Subject: [PATCH 15/15] Add conditional compilation to TFMessageMsgSerializer for ROS2 --- .../Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs index e5b199de..a894cdbc 100644 --- a/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs +++ b/Assets/UnitySensorsROS/Runtime/Scripts/Serializers/Tf2Msgs/TFMessageMsgSerializer.cs @@ -38,7 +38,10 @@ public override TFMessageMsg Serialize() TransformStampedMsg transform = new TransformStampedMsg(); transform.header = new HeaderMsg(); transform.header.stamp = headerMsg.stamp; +#if ROS2 +#else transform.header.seq = headerMsg.seq; +#endif transform.header.frame_id = data.frame_id_parent; transform.child_frame_id = data.frame_id_child; transform.transform.translation = data.position.To();