From 0db9bd839b2836c5ce00f08848541b5526c793c1 Mon Sep 17 00:00:00 2001 From: BytingBulldogs3539 Date: Fri, 29 Dec 2023 03:19:44 -0500 Subject: [PATCH] Fix Libcamera exposure bugs With ov9281 exposure 0 through 6 do not actually do anything. Gain of 0 would also enable auto exposure. --- .../vision/camera/LibcameraGpuSettables.java | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java index 45aefb5fc0..39015f149d 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java @@ -132,24 +132,21 @@ public void setExposure(double exposure) { // Auto-exposure is active right now, don't set anything. return; } + MathUtils.map(exposure, 0.0, 100.0, 0.1, 100); // HACKS! // If we set exposure too low, libcamera crashes or slows down // Very weird and smelly // For now, band-aid this by just not setting it lower than the "it breaks" limit - // is different depending on camera. + // is different depending on camera. if (sensorModel == LibCameraJNI.SensorModel.OV9281) { - if (exposure < 6.0) { - exposure = 6.0; - } + exposure = MathUtils.map(exposure, 0.1, 100.0, 6.0, 100); } else if (sensorModel == LibCameraJNI.SensorModel.OV5647) { - if (exposure < 0.7) { - exposure = 0.7; - } + exposure = MathUtils.map(exposure, 0.1, 100.0, 0.7, 100); } lastManualExposure = exposure; - var success = LibCameraJNI.setExposure(r_ptr, (int) Math.round(exposure) * 800); + var success = LibCameraJNI.setExposure(r_ptr, (int) (exposure * 800)); if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera exposure"); } @@ -164,8 +161,7 @@ public void setBrightness(int brightness) { @Override public void setGain(int gain) { lastGain = gain; - // TODO units here seem odd -- 5ish seems legit? So divide by 10 - var success = LibCameraJNI.setAnalogGain(r_ptr, gain / 10.0); + var success = LibCameraJNI.setAnalogGain(r_ptr, MathUtils.map(gain, 0.0, 100.0, 1, 10)); if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera gain"); }