Skip to content

Commit

Permalink
Fix grayscale passthrough (#1083)
Browse files Browse the repository at this point in the history
Fix grayscale passthrough with libcamera. Additionally fixes issue #1091.

Must go with PhotonVision/photon-libcamera-gl-driver#11.

When grayscale passthrough is used currently the frames that are returned do not have the type grayscale so calculations that need grayscale to not run. With these changes pipelines that need grayscale will now run and properly display fps.
  • Loading branch information
BytingBulldogs3539 authored Jan 3, 2024
1 parent 341954c commit e685334
Show file tree
Hide file tree
Showing 3 changed files with 23 additions and 16 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ ext {
openCVversion = "4.8.0-2"
joglVersion = "2.4.0-rc-20200307"
javalinVersion = "5.6.2"
photonGlDriverLibVersion = "dev-v2023.1.0-6-g5e6f7fa"
photonGlDriverLibVersion = "dev-v2023.1.0-8-g38bbe74"
frcYear = "2024"

pubVersion = versionString
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
package org.photonvision.vision.camera;

import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.Pair;
import edu.wpi.first.util.PixelFormat;
import java.util.HashMap;
Expand Down Expand Up @@ -119,23 +120,28 @@ public void setExposure(double exposure) {
return;
}

// Store the exposure for use when we need to recreate the camera.
lastManualExposure = exposure;

// Minimum exposure can't be below 1uS cause otherwise it would be 0 and 0 is auto exposure.
double minExposure = 1;

// 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.
// All units are uS.
if (sensorModel == LibCameraJNI.SensorModel.OV9281) {
if (exposure < 6.0) {
exposure = 6.0;
}
minExposure = 4800;
} else if (sensorModel == LibCameraJNI.SensorModel.OV5647) {
if (exposure < 0.7) {
exposure = 0.7;
}
minExposure = 560;
}
// 80,000 uS seems like an exposure value that will be greater than ever needed while giving
// enough control over exposure.
exposure = MathUtils.map(exposure, 0, 100, minExposure, 80000);

lastManualExposure = exposure;
var success = LibCameraJNI.setExposure(r_ptr, (int) Math.round(exposure) * 800);
var success = LibCameraJNI.setExposure(r_ptr, (int) exposure);
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera exposure");
}

Expand All @@ -150,8 +156,12 @@ 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);

// Map and clamp gain to values between 1 and 10 (libcamera min and gain that just seems higher
// than ever needed) from 0 to 100 (UI values).
var success =
LibCameraJNI.setAnalogGain(
r_ptr, MathUtil.clamp(MathUtils.map(gain, 0.0, 100.0, 1.0, 10.0), 1.0, 10.0));
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera gain");
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
import org.opencv.core.Mat;
import org.photonvision.common.util.math.MathUtils;
import org.photonvision.raspi.LibCameraJNI;
import org.photonvision.raspi.LibCameraJNI.SensorModel;
import org.photonvision.vision.camera.LibcameraGpuSettables;
import org.photonvision.vision.frame.Frame;
import org.photonvision.vision.frame.FrameProvider;
Expand Down Expand Up @@ -91,9 +90,7 @@ public Frame get() {

@Override
public void requestFrameThresholdType(FrameThresholdType type) {
if (settables.getModel() == SensorModel.OV9281 && type.equals(FrameThresholdType.GREYSCALE))
LibCameraJNI.setGpuProcessType(settables.r_ptr, 4); // 4 = Grayscale pass through.
else LibCameraJNI.setGpuProcessType(settables.r_ptr, type.ordinal());
LibCameraJNI.setGpuProcessType(settables.r_ptr, type.ordinal());
}

@Override
Expand Down

0 comments on commit e685334

Please sign in to comment.