private IEnumerator UpdateLidarLines() { // Setting up Compute Buffers int kernelHandle = computeShader.FindKernel("CSMain"); SetCameraBuffers(computeShader, "CSMain", lidarCameras); computeShader.SetTexture(kernelHandle, "sphericalMaskImage", sphericalMaskImage); computeShader.SetBuffer(kernelHandle, "sphericalPixelCoordinates", pixelCoordinatesBuffer); UnifiedArray <Vector3> particleUnifiedArray = new UnifiedArray <Vector3>(NrOfCameras * NrOfLasers * LidarHorisontalRes, sizeof(float) * 3, "lines"); particleUnifiedArray.SetBuffer(computeShader, "CSMain"); lidarDataByte = new UnifiedArray <byte>(NrOfCameras * NrOfLasers * LidarHorisontalRes, sizeof(float) * 6, "LidarData"); lidarDataByte.SetBuffer(computeShader, "CSMain"); lidarData = new UnifiedArray <LidarFieldData>(NrOfCameras * NrOfLasers * LidarHorisontalRes, sizeof(float) * 6, "LidarData2"); lidarData.SetBuffer(computeShader, "CSMain"); while (true) { computeShader.Dispatch(kernelHandle, (int)Mathf.Ceil((float)NrOfCameras * (float)NrOfLasers * (float)LidarHorisontalRes / 1024.0f), 1, 1); var request = AsyncGPUReadback.Request(particleUnifiedArray.buffer); yield return(new WaitUntil(() => request.done)); particleUnifiedArray.nativeArray = request.GetData <Vector3>(); if (ShowPointCloud) { particleMesh.SetVertices(particleUnifiedArray.nativeArray); } var request2 = AsyncGPUReadback.Request(lidarDataByte.buffer); yield return(new WaitUntil(() => request2.done)); lidarDataByte.nativeArray = request2.GetData <byte>(); byte[] LidarByteArray = lidarDataByte.nativeArray.ToArray(); var request3 = AsyncGPUReadback.Request(lidarData.buffer); yield return(new WaitUntil(() => request3.done)); lidarData.nativeArray = request3.GetData <LidarFieldData>(); // https://answers.unity.com/questions/1581776/bytearray-impossible-to-convert-1.html // Vær obs på om systemene kjører big / small endian var stringarray = System.BitConverter.ToSingle(LidarByteArray, 0); Debug.Log("x in bytes: " + stringarray.ToString()); Debug.Log("Intesnsity: " + lidarData.nativeArray[0].intensity.ToString()); } }
public static int[] ArrayAllocator(int length, ComputeShader shader) { string kernelName = "QuickArrayAllocation"; UnifiedArray <int> array = new UnifiedArray <int>(length, sizeof(int), "array"); array.SetBuffer(shader, kernelName); shader.SetInt("arrayLength", length); return(array.SynchUpdate(shader, kernelName).array); }
void Start() { CameraSetup(); int kernelIndex = cameraShader.FindKernel("CSMain"); cameraData = new UnifiedArray <byte>(PixelHeight * PixelWidth, sizeof(float) * 3, "CameraData"); cameraData.SetBuffer(cameraShader, "CSMain"); cameraShader.SetTexture(kernelIndex, "RenderTexture", camera.targetTexture); cameraShader.SetInt("Width", PixelWidth / ImageCrop); cameraShader.SetInt("Height", PixelHeight / ImageCrop); }
void Start() { // Setting User information WidthRes /= NrOfCameras; float lidarVerticalAngle = VerticalAngle; HeightRes = (int)(WidthRes * Mathf.Tan(lidarVerticalAngle * Mathf.Deg2Rad / 2) / Mathf.Sin(Mathf.PI / NrOfCameras)); VerticalAngle = Mathf.Rad2Deg * 2 * Mathf.Atan(Mathf.Tan(lidarVerticalAngle * Mathf.Deg2Rad / 2) / Mathf.Cos(Mathf.PI / NrOfCameras)); NumberOfDepthPixels = (uint)WidthRes * (uint)HeightRes * (uint)NrOfCameras; NumberOfLidarPoints = (uint)NrOfLasers * (uint)LidarHorisontalRes * (uint)NrOfCameras; // Settup Game objects pointCloud = GetComponent <PointCloudManager>(); pointCloud.SetupPointCloud((int)NumberOfLidarPoints); var frustum = new CameraFrustum(WidthRes, MaxDistance, MinDistance, 2 * Mathf.PI / NrOfCameras, lidarVerticalAngle * Mathf.Deg2Rad); depthCameras = new DepthCameras(NrOfCameras, frustum, this.transform, lidarShader, "CSMain"); lidarCameras = depthCameras.cameras; projectionFilter = GetComponent <SphericalProjectionFilter>(); projectionFilter.SetupSphericalProjectionFilter(LidarHorisontalRes, NrOfLasers, frustum); pixelCoordinatesBuffer = projectionFilter.filterCoordinates.buffer; // Setting up Compute Buffers kernelHandle = lidarShader.FindKernel("CSMain"); lidarShader.SetBuffer(kernelHandle, "sphericalPixelCoordinates", pixelCoordinatesBuffer); lidarShader.SetInt("N_theta", LidarHorisontalRes); lidarShader.SetInt("N_phi", NrOfLasers); lidarShader.SetFloat("rayDropProbability", rayDropProbability); UnifiedArray <uint> RandomStateVector = new UnifiedArray <uint>(NrOfCameras * NrOfLasers * LidarHorisontalRes, sizeof(float), "_state_xorshift"); RandomStateVector.SetBuffer(lidarShader, "CSMain"); RandomStateVector.SetBuffer(lidarShader, "RNG_Initialize"); RandomStateVector.SynchUpdate(lidarShader, "RNG_Initialize"); particleUnifiedArray = new UnifiedArray <Vector3>(NrOfCameras * NrOfLasers * LidarHorisontalRes, sizeof(float) * 3, "lines"); particleUnifiedArray.SetBuffer(lidarShader, "CSMain"); lidarDataByte = new UnifiedArray <byte>(NrOfCameras * NrOfLasers * LidarHorisontalRes, sizeof(float) * 6, "LidarData"); lidarDataByte.SetBuffer(lidarShader, "CSMain"); }
private IEnumerator UpdateRadar() { // Set Global Buffers computeShader.SetMatrix("inv_CameraMatrix", radarCameras[0].projectionMatrix.inverse); computeShader.SetInt("ImageWidthRes", WidthRes); computeShader.SetInt("ImageHeightRes", HeightRes); computeShader.SetInt("NrOfImages", NrOfCameras); computeShader.SetInt("radarResolution", radarSpokeResolution); computeShader.SetInt("radarSweepResolution", radarSweepResolution); computeShader.SetFloat("MaxDist", MaxDistance); computeShader.SetFloat("MinDist", MinDistance); computeShader.SetFloat("AntennaGainDbi", AntennaGainDbi); computeShader.SetFloat("PowerW", PowerW); computeShader.SetFloat("RadarFrequencyGhz", RadarFrequencyGhz); computeShader.SetFloat("SpokeAngle", SpokeAngle); // Radar Spokes buffers int RadarSpokesHandle = computeShader.FindKernel("RadarSpokes"); computeShader.SetTexture(RadarSpokesHandle, "RadarCharacteristics", RadiationPattern); int dataSize = sizeof(int); ComputeBuffer RadarSpokesIntBuffer = new ComputeBuffer(radarSpokeResolution * radarSweepResolution, dataSize); RadarSpokesInt = new NativeArray <int>(radarSpokeResolution * radarSweepResolution, Allocator.Temp, NativeArrayOptions.ClearMemory); RadarSpokesIntBuffer.SetData(RadarSpokesInt); computeShader.SetBuffer(RadarSpokesHandle, "RadarSpokesInt", RadarSpokesIntBuffer); for (int i = 0; i < radarCameras.Length; i++) { Quaternion angle = Quaternion.Euler(0, i * 360.0f / NrOfCameras, 0); Matrix4x4 m = Matrix4x4.Rotate(angle); computeShader.SetTexture(RadarSpokesHandle, "depthImage" + i.ToString(), radarCameras[i].targetTexture); computeShader.SetMatrix("CameraRotationMatrix" + i.ToString(), m); } // Radar range Convolution buffers int RadarRangeCovolutionHandle = computeShader.FindKernel("RadarRangeCovolution"); computeShader.SetBuffer(RadarRangeCovolutionHandle, "RadarSpokesInt", RadarSpokesIntBuffer); dataSize = sizeof(float); ComputeBuffer RadarSpokesFloatBuffer = new ComputeBuffer(radarSpokeResolution * radarSweepResolution, dataSize); RadarSpokesFloat = new NativeArray <float>(radarSpokeResolution * radarSweepResolution, Allocator.Temp, NativeArrayOptions.ClearMemory); RadarSpokesFloatBuffer.SetData(RadarSpokesFloat); computeShader.SetBuffer(RadarRangeCovolutionHandle, "RadarSpokesFloat", RadarSpokesFloatBuffer); // Radar spoke max buffers int RadarSpokeMax = computeShader.FindKernel("FindRadarSpokeMax"); ComputeBuffer MaxSpokesBuffer = new ComputeBuffer(radarSweepResolution, sizeof(float)); NativeArray <float> MaxSpokes = new NativeArray <float>(radarSweepResolution, Allocator.Temp, NativeArrayOptions.ClearMemory); MaxSpokesBuffer.SetData(MaxSpokes); computeShader.SetBuffer(RadarSpokeMax, "MaxSpokes", MaxSpokesBuffer); computeShader.SetBuffer(RadarSpokeMax, "RadarSpokesFloat", RadarSpokesFloatBuffer); // Radar plot image buffers int RadarPlotImageHandle = computeShader.FindKernel("CreateRadarPlotImage"); if (RadarPlotExternalImage != null) { dataSize = 24; RadarPlotImage = new RenderTexture(RadarPlotExternalImage.width, RadarPlotExternalImage.height, dataSize); RadarPlotImage.enableRandomWrite = true; RadarPlotImage.Create(); computeShader.SetTexture(RadarPlotImageHandle, "plotImage", RadarPlotImage); computeShader.SetBuffer(RadarPlotImageHandle, "RadarSpokesFloat", RadarSpokesFloatBuffer); computeShader.SetBuffer(RadarPlotImageHandle, "MaxSpokes", MaxSpokesBuffer); } // Radar spoke image buffers int RadarSpokeImageHandle = computeShader.FindKernel("CreateRadarSpokeImage"); if (RadarSpokeExternalImage != null) { dataSize = 24; RadarSpokeImage = new RenderTexture(RadarSpokeExternalImage.width, RadarSpokeExternalImage.height, dataSize); RadarSpokeImage.enableRandomWrite = true; RadarSpokeImage.Create(); computeShader.SetTexture(RadarSpokeImageHandle, "spokeImage", RadarSpokeImage); computeShader.SetBuffer(RadarSpokeImageHandle, "RadarSpokesFloat", RadarSpokesFloatBuffer); computeShader.SetBuffer(RadarSpokeImageHandle, "MaxSpokes", MaxSpokesBuffer); } // Radar Data string radarDataKernel = "RadarDataKernel"; string timeInSecondsBuffer = "timeInSeconds"; string azimuthBuffer = "azimuth"; string radarDataBuffer = "spokeData"; UnifiedArray <byte> radarData = new UnifiedArray <byte>(radarSweepResolution * radarSpokeResolution / 4, sizeof(uint), radarDataBuffer); radarData.SetBuffer(computeShader, radarDataKernel); UnifiedArray <float> azimuth = new UnifiedArray <float>(radarSweepResolution, sizeof(float), azimuthBuffer);; azimuth.SetBuffer(computeShader, radarDataKernel); UnifiedArray <double> timeInSeconds = new UnifiedArray <double>(radarSweepResolution, sizeof(double), timeInSecondsBuffer);; timeInSeconds.SetBuffer(computeShader, radarDataKernel); int radarDataKernelHandle = computeShader.FindKernel(radarDataKernel); computeShader.SetBuffer(radarDataKernelHandle, "RadarSpokesFloat", RadarSpokesFloatBuffer); computeShader.SetBuffer(radarDataKernelHandle, "MaxSpokes", MaxSpokesBuffer); ComputeBuffer timeArray = new ComputeBuffer(2, sizeof(double)); double[] timeArr = new double[2] { OSPtime, nextOSPtime }; timeArray.SetData(timeArr); computeShader.SetBuffer(radarDataKernelHandle, "timeArray", timeArray); // Radar clear buffers int ClearKernelHandle = computeShader.FindKernel("ClearRadar"); computeShader.SetBuffer(ClearKernelHandle, "RadarSpokesInt", RadarSpokesIntBuffer); // Fetch data from GPU float tempSens = -1; float tempSpokeAngle = -1; while (true) { // Check change in Inspector Variables if (Sensitivity != tempSens) { computeShader.SetFloat("Sensitivity", Sensitivity); tempSens = Sensitivity; } if (SpokeAngle != tempSpokeAngle) { computeShader.SetFloat("SpokeAngle", SpokeAngle); tempSpokeAngle = SpokeAngle; } timeArr[0] = OSPtime; timeArr[1] = nextOSPtime; timeArray.SetData(timeArr); computeShader.SetBuffer(radarDataKernelHandle, "timeArray", timeArray); // Create and Radar Data computeShader.Dispatch(RadarSpokesHandle, (int)Mathf.Ceil(NrOfCameras * WidthRes / 32), (int)Mathf.Ceil(HeightRes / 32), 1); computeShader.Dispatch(RadarRangeCovolutionHandle, (int)Mathf.Ceil(radarSweepResolution / 512), 1, 1); computeShader.Dispatch(RadarSpokeMax, (int)Mathf.Ceil(radarSweepResolution / 512), 1, 1); computeShader.Dispatch(radarDataKernelHandle, (int)Mathf.Ceil(radarSweepResolution / 512), 1, 1); // Recieve and send radar data var request2 = AsyncGPUReadback.Request(radarData.buffer); yield return(new WaitUntil(() => request2.done)); radarData.AsynchUpdate(request2); var request3 = AsyncGPUReadback.Request(azimuth.buffer); yield return(new WaitUntil(() => request3.done)); azimuth.AsynchUpdate(request3); var request4 = AsyncGPUReadback.Request(timeInSeconds.buffer); yield return(new WaitUntil(() => request4.done)); timeInSeconds.AsynchUpdate(request4); message = new RadarMessage(radarData.array, timeInSeconds.array, azimuth.array, (uint)MinDistance, (uint)MaxDistance, (uint)radarSpokeResolution); gate = true; // Debugging Images if (RadarPlotExternalImage != null) { computeShader.Dispatch(RadarPlotImageHandle, (int)Mathf.Ceil(RadarPlotImage.width / 32), (int)Mathf.Ceil(RadarPlotImage.height / 32), 1); } if (RadarSpokeExternalImage != null) { computeShader.Dispatch(RadarSpokeImageHandle, (int)Mathf.Ceil(RadarSpokeImage.width / 32), (int)Mathf.Ceil(RadarSpokeImage.height / 32), 1); } // Clear GPU memory computeShader.Dispatch(ClearKernelHandle, (int)Mathf.Ceil((radarSpokeResolution * radarSweepResolution) / 1024), 1, 1); } }