Skip to content

Commit

Permalink
Merge pull request #189 from Field-Robotics-Japan/pr186/beta/v2.x.x
Browse files Browse the repository at this point in the history
ROS Example  Added for PR #186
  • Loading branch information
RyodoTanaka authored Mar 3, 2025
2 parents d2b31f1 + aa52b6d commit 1d788cd
Show file tree
Hide file tree
Showing 17 changed files with 1,655 additions and 53 deletions.
103 changes: 103 additions & 0 deletions Assets/UnitySensors/Runtime/Prefabs/Camera/PanoramicCamera.prefab
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
%YAML 1.1
%TAG !u! tag:unity3d.com,2011:
--- !u!1 &6023160553514482222
GameObject:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
serializedVersion: 6
m_Component:
- component: {fileID: 6023160553514482209}
- component: {fileID: 6023160553514482210}
- component: {fileID: -5894630385440489856}
m_Layer: 0
m_Name: PanoramicCamera
m_TagString: Untagged
m_Icon: {fileID: 0}
m_NavMeshLayer: 0
m_StaticEditorFlags: 0
m_IsActive: 1
--- !u!4 &6023160553514482209
Transform:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
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_LocalEulerAnglesHint: {x: 0, y: 0, z: 0}
--- !u!20 &6023160553514482210
Camera:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 6023160553514482222}
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: 0
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!114 &-5894630385440489856
MonoBehaviour:
m_ObjectHideFlags: 0
m_CorrespondingSourceObject: {fileID: 0}
m_PrefabInstance: {fileID: 0}
m_PrefabAsset: {fileID: 0}
m_GameObject: {fileID: 6023160553514482222}
m_Enabled: 1
m_EditorHideFlags: 0
m_Script: {fileID: 11500000, guid: 6618a3eeb546cbde1b85333be7bf7400, type: 3}
m_Name:
m_EditorClassIdentifier:
_frequency: 20
<resolution>k__BackingField: {x: 1920, y: 270}
<fov>k__BackingField: 30
<minRange>k__BackingField: 0.05
<maxRange>k__BackingField: 100

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

68 changes: 30 additions & 38 deletions Assets/UnitySensors/Runtime/Scripts/Sensors/Camera/CameraSensor.cs
Original file line number Diff line number Diff line change
Expand Up @@ -8,51 +8,43 @@ namespace UnitySensors.Sensor.Camera
[RequireComponent(typeof(UnityEngine.Camera))]
public abstract class CameraSensor : UnitySensor, ITextureInterface
{
[SerializeField]
private Vector2Int _resolution = new Vector2Int(640, 480);
[SerializeField]
private float _fov = 30.0f;
[SerializeField]
private float _minRange = 0.05f;
[SerializeField]
private float _maxRange = 100.0f;
[field: SerializeField] public Vector2Int resolution { get; protected set; } = new(640, 480);
[field: SerializeField] public float fov { get; protected set; } = 30.0f;
[field: SerializeField] public float minRange { get; protected set; } = 0.05f;
[field: SerializeField] public float maxRange { get; protected set; } = 100.0f;

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"; }
public UnityEngine.Camera sensorCamera { get; protected set; }
public byte[] data { get; protected set; }
public string encoding { get; protected set; }
public int width { get => resolution.x; }
public int height { get => resolution.y; }
public Texture2D texture { get; protected set; }

protected RenderTexture _rt;

protected override void Init()
{
_m_camera = GetComponent<UnityEngine.Camera>();
_m_camera.fieldOfView = _fov;
_m_camera.nearClipPlane = _minRange;
_m_camera.farClipPlane = _maxRange;

_rt = new RenderTexture(_resolution.x, _resolution.y, 16, RenderTextureFormat.ARGB32);
_m_camera.targetTexture = _rt;
sensorCamera = GetComponent<UnityEngine.Camera>();
sensorCamera.fieldOfView = fov;
sensorCamera.nearClipPlane = minRange;
sensorCamera.farClipPlane = maxRange;

_texture = new Texture2D(width, height, TextureFormat.RGB24, false);
if( _rt == null )
{
_rt = new RenderTexture(width, height, 16, RenderTextureFormat.ARGB32);
sensorCamera.targetTexture = _rt;
}

_data = new byte[width * height * 3];
texture = new Texture2D(width, height, TextureFormat.RGB24, false);
data = new byte[width * height * 3];
encoding = "rgb8";
}

protected override void UpdateSensor()
{
if (!LoadTexture()) return;

if (onSensorUpdated != null)
onSensorUpdated.Invoke();
onSensorUpdated?.Invoke();
}

protected bool LoadTexture()
Expand All @@ -71,17 +63,17 @@ protected bool LoadTexture()
int j=width*(height-1)*4;
for(int y=0; y<height; y++){
for(int x=0; x<width; x++) {
_data[i+0] = dataBuffer[j+1];
_data[i+1] = dataBuffer[j+2];
_data[i+2] = dataBuffer[j+3];
data[i+0] = dataBuffer[j+1];
data[i+1] = dataBuffer[j+2];
data[i+2] = dataBuffer[j+3];
i+=3;
j+=4;
}
j -= width << 3; // width * 2 * 3;
}

_texture.LoadRawTextureData(_data);
_texture.Apply();
texture.LoadRawTextureData(data);
texture.Apply();

result = true;
}
Expand All @@ -95,7 +87,7 @@ protected override void OnSensorDestroy()
if (_rt != null)
{
// Dispose the frame texture.
m_camera.targetTexture = null;
sensorCamera.targetTexture = null;
Destroy(_rt);
_rt = null;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ protected override void Init()
base.Init();

_mat = new Material(Shader.Find("UnitySensors/Color2Depth"));
float f = m_camera.farClipPlane;
float f = sensorCamera.farClipPlane;
_mat.SetFloat("_F", f);

SetupDirections();
Expand All @@ -46,17 +46,17 @@ protected override void Init()

private void SetupDirections()
{
_pointsNum = resolution.x * resolution.y;
_pointsNum = width * height;

_directions = new NativeArray<float3>(_pointsNum, Allocator.Persistent);

float z = resolution.y * 0.5f / Mathf.Tan(m_camera.fieldOfView * 0.5f * Mathf.Deg2Rad);
for (int y = 0; y < resolution.y; y++)
float z = height * 0.5f / Mathf.Tan(sensorCamera.fieldOfView * 0.5f * Mathf.Deg2Rad);
for (int y = 0; y < height; y++)
{
for (int x = 0; x < resolution.x; x++)
for (int x = 0; x < width; x++)
{
Vector3 vec = new Vector3(-resolution.x / 2 + x, -resolution.y / 2 + y, z);
_directions[y * resolution.x + x] = vec.normalized;
Vector3 vec = new Vector3(-width / 2 + x, -height / 2 + y, z);
_directions[y * width + x] = vec.normalized;
}
}
}
Expand All @@ -79,12 +79,12 @@ private void SetupJob()

_textureToPointsJob = new ITextureToPointsJob()
{
near= m_camera.nearClipPlane,
far = m_camera.farClipPlane,
near = sensorCamera.nearClipPlane,
far = sensorCamera.farClipPlane,
directions = _directions,
pixels = texture.GetPixelData<Color>(0),
noises = _noises,
points = _pointCloud.points
pixels = texture.GetPixelData<Color>(0),
noises = _noises,
points = _pointCloud.points
};
}

Expand All @@ -97,8 +97,7 @@ protected override void UpdateSensor()
JobHandle.ScheduleBatchedJobs();
_jobHandle.Complete();

if (onSensorUpdated != null)
onSensorUpdated.Invoke();
onSensorUpdated?.Invoke();
}

protected override void OnSensorDestroy()
Expand Down

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
using UnityEngine;

namespace UnitySensors.Sensor.Camera
{
public class PanoramicCameraSensor : CameraSensor
{
private Material _mat;
private RenderTexture _cubemap;

protected override void Init()
{
_cubemap = new RenderTexture(1024, 1024, 16, RenderTextureFormat.ARGB32)
{
dimension = UnityEngine.Rendering.TextureDimension.Cube
};
_rt = new RenderTexture(width, height, 16, RenderTextureFormat.ARGB32);
_mat = new Material(Shader.Find("UnitySensors/Panoramic"));
base.Init();
}

protected override void UpdateSensor()
{
_mat.SetVector("_Rotation", transform.eulerAngles);
sensorCamera.RenderToCubemap(_cubemap);
Graphics.Blit(_cubemap, _rt, _mat);

if (!LoadTexture()) return;
onSensorUpdated?.Invoke();
}
}
}

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Loading

0 comments on commit 1d788cd

Please sign in to comment.