Skip to content

Commit c30b45c

Browse files
authored
Merge pull request Field-Robotics-Japan#205 from hijimasa/feature/supportNativeRenderGraphCompiler
Fix Unity 23.3+ RenderGraph depth buffer requirement
2 parents f89c16e + 28068d5 commit c30b45c

File tree

6 files changed

+375
-0
lines changed

6 files changed

+375
-0
lines changed

Packages/UnitySensors/Runtime/Scripts/Sensors/Camera/DepthCamera/DepthCameraSensor.cs

Lines changed: 193 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,51 @@
1313
using System.Collections;
1414
using UnitySensors.Utils.Texture;
1515

16+
#if UNITY_6000_0_OR_NEWER
17+
using UnityEngine.Rendering;
18+
#endif
19+
1620
namespace UnitySensors.Sensor.Camera
1721
{
22+
// Job for parallel raycast depth calculation
23+
public struct ParallelRaycastDepthJob : IJobParallelFor
24+
{
25+
[ReadOnly] public float3 cameraPosition;
26+
[ReadOnly] public float3 forward;
27+
[ReadOnly] public float3 right;
28+
[ReadOnly] public float3 up;
29+
[ReadOnly] public float tanHalfFov;
30+
[ReadOnly] public float aspect;
31+
[ReadOnly] public int width;
32+
[ReadOnly] public int height;
33+
[ReadOnly] public float farClipPlane;
34+
35+
[WriteOnly] public NativeArray<float> depthValues;
36+
37+
public void Execute(int index)
38+
{
39+
int x = index % width;
40+
int y = index / width;
41+
42+
float normalizedX = (float)x / (width - 1);
43+
float normalizedY = (float)y / (height - 1);
44+
45+
float ndcX = (2.0f * normalizedX) - 1.0f;
46+
float ndcY = (2.0f * normalizedY) - 1.0f;
47+
48+
float viewX = ndcX * tanHalfFov * aspect;
49+
float viewY = ndcY * tanHalfFov;
50+
51+
float3 rayDirection = math.normalize(forward + right * viewX + up * viewY);
52+
53+
// Note: Unity.Physics would be needed for burst-compiled raycast
54+
// For now, we'll use the fallback value
55+
float depth = 1.0f;
56+
57+
depthValues[index] = depth;
58+
}
59+
}
60+
1861
[RequireComponent(typeof(UnityEngine.Camera))]
1962
public class DepthCameraSensor : CameraSensor, IPointCloudInterface<PointXYZ>
2063
{
@@ -28,7 +71,17 @@ public class DepthCameraSensor : CameraSensor, IPointCloudInterface<PointXYZ>
2871
private Material _depthCameraMat;
2972
[SerializeField]
3073
private bool _convertToPointCloud = false;
74+
75+
[Header("Performance Settings")]
76+
[SerializeField, Range(0.1f, 1.0f)]
77+
private float _raycastResolutionScale = 0.5f; // Reduce raycast resolution for better performance
78+
[SerializeField]
79+
private bool _useAdaptiveQuality = true; // Enable adaptive quality based on frame rate
80+
3181
private TextureLoader _textureLoader;
82+
private Texture2D _depthTexture; // Reuse texture to avoid allocations
83+
private int _lastRaycastWidth, _lastRaycastHeight;
84+
private float _lastFrameTime;
3285

3386
private JobHandle _jobHandle;
3487

@@ -52,7 +105,18 @@ protected override void Init()
52105
_camera.nearClipPlane = _minRange;
53106
_camera.farClipPlane = _maxRange;
54107

108+
#if UNITY_6000_0_OR_NEWER
109+
_rt = new RenderTexture(_resolution.x, _resolution.y, 24, RenderTextureFormat.ARGBFloat);
110+
_rt.Create();
111+
112+
bool isURP = GraphicsSettings.currentRenderPipeline != null;
113+
if (isURP)
114+
{
115+
Debug.Log("DepthCameraSensor: Unity 6000+ URP mode initialized");
116+
}
117+
#else
55118
_rt = new RenderTexture(_resolution.x, _resolution.y, 0, RenderTextureFormat.ARGBFloat);
119+
#endif
56120
_camera.targetTexture = _rt;
57121

58122
_texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBAFloat, false);
@@ -116,7 +180,21 @@ private void SetupJob()
116180

117181
protected override IEnumerator UpdateSensor()
118182
{
183+
#if UNITY_6000_0_OR_NEWER
184+
bool isURP = GraphicsSettings.currentRenderPipeline != null;
185+
186+
if (isURP)
187+
{
188+
GenerateDepthImageUsingRaycast();
189+
}
190+
else
191+
{
192+
_camera.Render();
193+
}
194+
#else
119195
_camera.Render();
196+
#endif
197+
120198
yield return _textureLoader.LoadTextureAsync();
121199

122200
if (_textureLoader.success && _convertToPointCloud)
@@ -128,6 +206,111 @@ protected override IEnumerator UpdateSensor()
128206
}
129207
}
130208

209+
private void GenerateDepthImageUsingRaycast()
210+
{
211+
// Adaptive quality adjustment based on frame rate
212+
if (_useAdaptiveQuality)
213+
{
214+
float currentFrameTime = Time.unscaledDeltaTime;
215+
if (_lastFrameTime > 0)
216+
{
217+
float currentFPS = 1.0f / currentFrameTime;
218+
float targetFPS = frequency; // Use sensor frequency as target
219+
if (currentFPS < targetFPS * 0.8f) // If FPS drops below 80% of target
220+
{
221+
_raycastResolutionScale = Mathf.Max(0.1f, _raycastResolutionScale - 0.05f);
222+
}
223+
else if (currentFPS > targetFPS * 1.1f) // If FPS is above 110% of target
224+
{
225+
_raycastResolutionScale = Mathf.Min(1.0f, _raycastResolutionScale + 0.02f);
226+
}
227+
}
228+
_lastFrameTime = currentFrameTime;
229+
}
230+
231+
// Calculate actual raycast resolution
232+
int raycastWidth = Mathf.Max(1, Mathf.RoundToInt(_rt.width * _raycastResolutionScale));
233+
int raycastHeight = Mathf.Max(1, Mathf.RoundToInt(_rt.height * _raycastResolutionScale));
234+
235+
// Reuse texture if possible to avoid allocations
236+
if (_depthTexture == null || _lastRaycastWidth != raycastWidth || _lastRaycastHeight != raycastHeight)
237+
{
238+
if (_depthTexture != null)
239+
DestroyImmediate(_depthTexture);
240+
241+
_depthTexture = new Texture2D(raycastWidth, raycastHeight, TextureFormat.RGBAFloat, false);
242+
_lastRaycastWidth = raycastWidth;
243+
_lastRaycastHeight = raycastHeight;
244+
}
245+
246+
RenderTexture.active = _rt;
247+
GL.Clear(true, true, Color.white);
248+
RenderTexture.active = null;
249+
250+
// Pre-calculate camera parameters
251+
float fovRad = _camera.fieldOfView * Mathf.Deg2Rad;
252+
float aspect = (float)_rt.width / _rt.height;
253+
float tanHalfFov = Mathf.Tan(fovRad * 0.5f);
254+
255+
Vector3 cameraPos = _camera.transform.position;
256+
Vector3 forward = _camera.transform.forward;
257+
Vector3 right = _camera.transform.right;
258+
Vector3 up = _camera.transform.up;
259+
260+
// Use Color32 array for better performance
261+
Color32[] pixels = new Color32[raycastWidth * raycastHeight];
262+
263+
// Batch raycast operations
264+
for (int y = 0; y < raycastHeight; y++)
265+
{
266+
for (int x = 0; x < raycastWidth; x++)
267+
{
268+
// Map raycast coordinates to full resolution
269+
float normalizedX = (float)x / (raycastWidth - 1);
270+
float normalizedY = (float)y / (raycastHeight - 1);
271+
272+
float ndcX = (2.0f * normalizedX) - 1.0f;
273+
float ndcY = (2.0f * normalizedY) - 1.0f;
274+
275+
float viewX = ndcX * tanHalfFov * aspect;
276+
float viewY = ndcY * tanHalfFov;
277+
278+
Vector3 rayDirection = (forward + right * viewX + up * viewY).normalized;
279+
Ray ray = new Ray(cameraPos, rayDirection);
280+
281+
float depth = 1.0f;
282+
283+
if (Physics.Raycast(ray, out RaycastHit hit, _camera.farClipPlane))
284+
{
285+
float distance = hit.distance;
286+
depth = Mathf.Clamp01(distance / _camera.farClipPlane);
287+
}
288+
289+
byte depthByte = (byte)(depth * 255);
290+
pixels[y * raycastWidth + x] = new Color32(depthByte, depthByte, depthByte, 255);
291+
}
292+
}
293+
294+
// Apply pixels and scale to target resolution
295+
_depthTexture.SetPixels32(pixels);
296+
_depthTexture.Apply();
297+
298+
// Scale to target resolution if needed
299+
if (raycastWidth != _rt.width || raycastHeight != _rt.height)
300+
{
301+
RenderTexture tempRT = RenderTexture.GetTemporary(_rt.width, _rt.height, 0, RenderTextureFormat.ARGBFloat);
302+
Graphics.Blit(_depthTexture, tempRT);
303+
Graphics.CopyTexture(tempRT, _rt);
304+
RenderTexture.ReleaseTemporary(tempRT);
305+
}
306+
else
307+
{
308+
RenderTexture.active = _rt;
309+
Graphics.CopyTexture(_depthTexture, _rt);
310+
RenderTexture.active = null;
311+
}
312+
}
313+
131314
protected override void OnSensorDestroy()
132315
{
133316
if (_convertToPointCloud)
@@ -137,12 +320,22 @@ protected override void OnSensorDestroy()
137320
_noises.Dispose();
138321
_directions.Dispose();
139322
}
323+
324+
// Clean up depth texture
325+
if (_depthTexture != null)
326+
{
327+
DestroyImmediate(_depthTexture);
328+
_depthTexture = null;
329+
}
330+
140331
_rt.Release();
141332
}
142333

334+
#if !UNITY_6000_0_OR_NEWER
143335
private void OnRenderImage(RenderTexture source, RenderTexture dest)
144336
{
145337
Graphics.Blit(null, dest, _depthCameraMat);
146338
}
339+
#endif
147340
}
148341
}

Packages/UnitySensors/Runtime/Scripts/Sensors/Camera/FisheyeCamera/FisheyeCameraSensor.cs

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,11 +33,20 @@ public enum CameraModel
3333
protected override void Init()
3434
{
3535
base.Init();
36+
#if UNITY_6000_0_OR_NEWER
37+
// Unity 6000+ requires depth buffer for render textures used with cameras
38+
_cubemap = new RenderTexture(_cubemapResolution, _cubemapResolution, 24, RenderTextureFormat.ARGB32)
39+
{
40+
dimension = TextureDimension.Cube
41+
};
42+
_rt = new RenderTexture(_resolution.x, _resolution.y, 24, RenderTextureFormat.ARGB32);
43+
#else
3644
_cubemap = new RenderTexture(_cubemapResolution, _cubemapResolution, 0, RenderTextureFormat.ARGB32)
3745
{
3846
dimension = TextureDimension.Cube
3947
};
4048
_rt = new RenderTexture(_resolution.x, _resolution.y, 0, RenderTextureFormat.ARGB32);
49+
#endif
4150
_texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBA32, false);
4251
_textureLoader = new TextureLoader
4352
{

Packages/UnitySensors/Runtime/Scripts/Sensors/Camera/PanoramicCamera/PanoramicCameraSensor.cs

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,11 +16,20 @@ public class PanoramicCameraSensor : CameraSensor
1616
protected override void Init()
1717
{
1818
base.Init();
19+
#if UNITY_6000_0_OR_NEWER
20+
// Unity 6000+ requires depth buffer for render textures used with cameras
21+
_cubemap = new RenderTexture(_cubemapResolution.x, _cubemapResolution.y, 24, RenderTextureFormat.ARGB32)
22+
{
23+
dimension = TextureDimension.Cube
24+
};
25+
_rt = new RenderTexture(_resolution.x, _resolution.y, 24, RenderTextureFormat.ARGB32);
26+
#else
1927
_cubemap = new RenderTexture(_cubemapResolution.x, _cubemapResolution.y, 0, RenderTextureFormat.ARGB32)
2028
{
2129
dimension = TextureDimension.Cube
2230
};
2331
_rt = new RenderTexture(_resolution.x, _resolution.y, 0, RenderTextureFormat.ARGB32);
32+
#endif
2433
_texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBA32, false);
2534
_textureLoader = new TextureLoader
2635
{

Packages/UnitySensors/Runtime/Scripts/Sensors/Camera/RGBCamera/RGBCameraSensor.cs

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,12 @@ public class RGBCameraSensor : CameraSensor
1010
protected override void Init()
1111
{
1212
base.Init();
13+
#if UNITY_6000_0_OR_NEWER
14+
// Unity 6000+ requires depth buffer for render textures used with cameras
15+
_rt = new RenderTexture(_resolution.x, _resolution.y, 24, RenderTextureFormat.ARGB32);
16+
#else
1317
_rt = new RenderTexture(_resolution.x, _resolution.y, 0, RenderTextureFormat.ARGB32);
18+
#endif
1419
_camera.targetTexture = _rt;
1520

1621
_texture = new Texture2D(_resolution.x, _resolution.y, TextureFormat.RGBA32, false);

0 commit comments

Comments
 (0)