Bug Fix Grab Bag (#688)

* Reordered ov video modes to be lowest-to-highest res

* Save off sensor model on init. Guard against low, crashy exposures.

* Pulled in matt's fixups from https://github.com/PhotonVision/photon-libcamera-gl-driver/suites/10144555465/artifacts/495489276

* Further autoexposure tweaks for picam v1

* Allow undercores in camera rename

* Additional guarding against output images being empty

* lock out auto-exposure on ov9281's

* Guarding stream pipelines against empty frames from cameras. Rearranged driver stream to resize first, then draw crosshairs (matchces with other pipelines now).

* NT Priority fixup - if client is sending commands on NT, its nt value should win over anything done from the UI

* Synchronous pipline adjustmet fix, method cleanup

* lint

* circle pipe and data publish bugfixes

* lint

* Pulled in matt's latest .so and re-enabled auto exposure on 9281's
This commit is contained in:
Chris Gerth
2023-01-03 21:53:04 -06:00
committed by GitHub
parent af6f5eb0c4
commit 8c8c32af1a
10 changed files with 139 additions and 114 deletions

View File

@@ -257,7 +257,7 @@ export default {
},
data: () => {
return {
re: RegExp("^[A-Za-z0-9 \\-)(]*[A-Za-z0-9][A-Za-z0-9 \\-)(.]*$"),
re: RegExp("^[A-Za-z0-9_ \\-)(]*[A-Za-z0-9][A-Za-z0-9_ \\-)(.]*$"),
isCameraNameEdit: false,
newCameraName: "",
cameraNameError: "",

View File

@@ -142,8 +142,8 @@ public class NTDataPublisher implements CVPipelineResultConsumer {
ts.rawBytesEntry.set(packet.getData());
ts.pipelineIndexPublisher.set(pipelineIndexSupplier.get());
ts.driverModePublisher.set(driverModeSupplier.getAsBoolean());
ts.pipelineIndexPublisher.setDefault(pipelineIndexSupplier.get());
ts.driverModePublisher.setDefault(driverModeSupplier.getAsBoolean());
ts.latencyMillisEntry.set(result.getLatencyMillis());
ts.hasTargetEntry.set(result.hasTargets());

View File

@@ -29,13 +29,15 @@ import org.photonvision.vision.processes.VisionSourceSettables;
public class LibcameraGpuSettables extends VisionSourceSettables {
private FPSRatedVideoMode currentVideoMode;
private double lastExposure = 50;
private double lastManualExposure = 50;
private int lastBrightness = 50;
private boolean lastExposureMode;
private boolean lastAutoExposureActive;
private int lastGain = 50;
private Pair<Integer, Integer> lastAwbGains = new Pair<>(18, 18);
private boolean m_initialized = false;
private final LibCameraJNI.SensorModel sensorModel;
private ImageRotationMode m_rotationMode;
public void setRotation(ImageRotationMode rotationMode) {
@@ -51,7 +53,7 @@ public class LibcameraGpuSettables extends VisionSourceSettables {
videoModes = new HashMap<>();
LibCameraJNI.SensorModel sensorModel = LibCameraJNI.getSensorModel();
sensorModel = LibCameraJNI.getSensorModel();
if (sensorModel == LibCameraJNI.SensorModel.IMX219) {
// Settings for the IMX219 sensor, which is used on the Pi Camera Module v2
@@ -72,13 +74,14 @@ public class LibcameraGpuSettables extends VisionSourceSettables {
6, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 3280 / 4, 2464 / 4, 15, 20, 1));
} else if (sensorModel == LibCameraJNI.SensorModel.OV9281) {
videoModes.put(
0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 800, 60, 60, 1));
0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, .39));
videoModes.put(
1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280 / 2, 800 / 2, 60, 60, 1));
videoModes.put(
2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, .39));
2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39));
videoModes.put(
3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39));
3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 800, 60, 60, 1));
} else {
if (sensorModel == LibCameraJNI.SensorModel.IMX477) {
LibcameraGpuSource.logger.warn(
@@ -114,20 +117,33 @@ public class LibcameraGpuSettables extends VisionSourceSettables {
@Override
public void setAutoExposure(boolean cameraAutoExposure) {
lastExposureMode = cameraAutoExposure;
// TODO (Matt) -- call LibCameraJNI's auto exposure function, when that exists
lastAutoExposureActive = cameraAutoExposure;
LibCameraJNI.setAutoExposure(cameraAutoExposure);
}
@Override
public void setExposure(double exposure) {
// Todo (Chris) - for now, handle auto exposure by using -1
if (exposure < 0.0) {
exposure = -1;
if (exposure < 0.0 || lastAutoExposureActive) {
// Auto-exposure is active right now, don't set anything.
return;
}
// TODO convert to uS
lastExposure = exposure;
// 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
// Limit is different depending on camera.
if (sensorModel == LibCameraJNI.SensorModel.OV9281) {
if (exposure < 6.0) {
exposure = 6.0;
}
} else if (sensorModel == LibCameraJNI.SensorModel.OV5647) {
if (exposure < 0.7) {
exposure = 0.7;
}
}
lastManualExposure = exposure;
var success = LibCameraJNI.setExposure((int) Math.round(exposure) * 800);
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera exposure");
}
@@ -150,19 +166,25 @@ public class LibcameraGpuSettables extends VisionSourceSettables {
@Override
public void setRedGain(int red) {
lastAwbGains = Pair.of(red, lastAwbGains.getSecond());
setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond());
if (sensorModel != LibCameraJNI.SensorModel.OV9281) {
lastAwbGains = Pair.of(red, lastAwbGains.getSecond());
setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond());
}
}
@Override
public void setBlueGain(int blue) {
lastAwbGains = Pair.of(lastAwbGains.getFirst(), blue);
setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond());
if (sensorModel != LibCameraJNI.SensorModel.OV9281) {
lastAwbGains = Pair.of(lastAwbGains.getFirst(), blue);
setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond());
}
}
public void setAwbGain(int red, int blue) {
var success = LibCameraJNI.setAwbGain(red / 10.0, blue / 10.0);
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera AWB gains");
if (sensorModel != LibCameraJNI.SensorModel.OV9281) {
var success = LibCameraJNI.setAwbGain(red / 10.0, blue / 10.0);
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera AWB gains");
}
}
@Override
@@ -202,8 +224,8 @@ public class LibcameraGpuSettables extends VisionSourceSettables {
// We don't store last settings on the native side, and when you change video mode these get
// reset on MMAL's end
setExposure(lastExposure);
setAutoExposure(lastExposureMode);
setExposure(lastManualExposure);
setAutoExposure(lastAutoExposureActive);
setBrightness(lastBrightness);
setGain(lastGain);
setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond());

View File

@@ -66,7 +66,7 @@ public class FindCirclesPipe
1.0,
params.minDist,
params.maxCannyThresh,
params.accuracy,
Math.max(1.0, params.accuracy),
minRadius,
maxRadius);
// Great, we now found the center point of the circle and it's radius, but we have no idea what

View File

@@ -77,18 +77,22 @@ public class DriverModePipeline
// apply pipes
var inputMat = frame.colorImage.getMat();
totalNanos += resizeImagePipe.run(inputMat).nanosElapsed;
boolean emptyIn = inputMat.empty();
if (!accelerated) {
var rotateImageResult = rotateImagePipe.run(inputMat);
totalNanos += rotateImageResult.nanosElapsed;
if (!emptyIn) {
if (!accelerated) {
var rotateImageResult = rotateImagePipe.run(inputMat);
totalNanos += rotateImageResult.nanosElapsed;
}
totalNanos += resizeImagePipe.run(inputMat).nanosElapsed;
var draw2dCrosshairResult = draw2dCrosshairPipe.run(Pair.of(inputMat, List.of()));
// calculate elapsed nanoseconds
totalNanos += draw2dCrosshairResult.nanosElapsed;
}
var draw2dCrosshairResult = draw2dCrosshairPipe.run(Pair.of(inputMat, List.of()));
// calculate elapsed nanoseconds
totalNanos += draw2dCrosshairResult.nanosElapsed;
var fpsResult = calculateFPSPipe.run(null);
var fps = fpsResult.output;

View File

@@ -110,65 +110,71 @@ public class OutputStreamPipeline {
boolean inEmpty = inMat.empty();
if (!inEmpty)
sumPipeNanosElapsed += pipeProfileNanos[0] = resizeImagePipe.run(inMat).nanosElapsed;
sumPipeNanosElapsed += pipeProfileNanos[1] = resizeImagePipe.run(outMat).nanosElapsed;
// Convert single-channel HSV output mat to 3-channel BGR in preparation for streaming
if (outMat.channels() == 1) {
var outputMatPipeResult = outputMatPipe.run(outMat);
sumPipeNanosElapsed += pipeProfileNanos[2] = outputMatPipeResult.nanosElapsed;
} else {
pipeProfileNanos[2] = 0;
}
boolean outEmpty = outMat.empty();
if (!outEmpty)
sumPipeNanosElapsed += pipeProfileNanos[1] = resizeImagePipe.run(outMat).nanosElapsed;
// Draw 2D Crosshair on output
var draw2dCrosshairResultOnInput = draw2dCrosshairPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[3] = draw2dCrosshairResultOnInput.nanosElapsed;
if (!(settings instanceof AprilTagPipelineSettings)) {
// If we're processing anything other than Apriltags...
var draw2dCrosshairResultOnOutput = draw2dCrosshairPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[4] = draw2dCrosshairResultOnOutput.nanosElapsed;
if (settings.solvePNPEnabled) {
// Draw 3D Targets on input and output if possible
pipeProfileNanos[5] = 0;
pipeProfileNanos[6] = 0;
pipeProfileNanos[7] = 0;
var drawOnOutputResult = draw3dTargetsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[8] = drawOnOutputResult.nanosElapsed;
// Only attempt drawing on a non-empty frame
if (!outEmpty) {
// Convert single-channel HSV output mat to 3-channel BGR in preparation for streaming
if (outMat.channels() == 1) {
var outputMatPipeResult = outputMatPipe.run(outMat);
sumPipeNanosElapsed += pipeProfileNanos[2] = outputMatPipeResult.nanosElapsed;
} else {
// Only draw 2d targets
pipeProfileNanos[5] = 0;
var draw2dTargetsOnOutput = draw2dTargetsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[6] = draw2dTargetsOnOutput.nanosElapsed;
pipeProfileNanos[7] = 0;
pipeProfileNanos[8] = 0;
pipeProfileNanos[2] = 0;
}
} else {
// If we are doing apriltags...
if (settings.solvePNPEnabled) {
// Draw 3d Apriltag markers (camera is calibrated and running in 3d mode)
pipeProfileNanos[5] = 0;
pipeProfileNanos[6] = 0;
// Draw 2D Crosshair on output
var draw2dCrosshairResultOnInput = draw2dCrosshairPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[3] = draw2dCrosshairResultOnInput.nanosElapsed;
var drawOnInputResult = draw3dAprilTagsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[7] = drawOnInputResult.nanosElapsed;
if (!(settings instanceof AprilTagPipelineSettings)) {
// If we're processing anything other than Apriltags...
pipeProfileNanos[8] = 0;
var draw2dCrosshairResultOnOutput = draw2dCrosshairPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[4] = draw2dCrosshairResultOnOutput.nanosElapsed;
if (settings.solvePNPEnabled) {
// Draw 3D Targets on input and output if possible
pipeProfileNanos[5] = 0;
pipeProfileNanos[6] = 0;
pipeProfileNanos[7] = 0;
var drawOnOutputResult = draw3dTargetsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[8] = drawOnOutputResult.nanosElapsed;
} else {
// Only draw 2d targets
pipeProfileNanos[5] = 0;
var draw2dTargetsOnOutput = draw2dTargetsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[6] = draw2dTargetsOnOutput.nanosElapsed;
pipeProfileNanos[7] = 0;
pipeProfileNanos[8] = 0;
}
} else {
// Draw 2d apriltag markers
var draw2dTargetsOnInput = draw2dAprilTagsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[5] = draw2dTargetsOnInput.nanosElapsed;
// If we are doing apriltags...
if (settings.solvePNPEnabled) {
// Draw 3d Apriltag markers (camera is calibrated and running in 3d mode)
pipeProfileNanos[5] = 0;
pipeProfileNanos[6] = 0;
pipeProfileNanos[6] = 0;
pipeProfileNanos[7] = 0;
pipeProfileNanos[8] = 0;
var drawOnInputResult = draw3dAprilTagsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[7] = drawOnInputResult.nanosElapsed;
pipeProfileNanos[8] = 0;
} else {
// Draw 2d apriltag markers
var draw2dTargetsOnInput = draw2dAprilTagsPipe.run(Pair.of(outMat, targetsToDraw));
sumPipeNanosElapsed += pipeProfileNanos[5] = draw2dTargetsOnInput.nanosElapsed;
pipeProfileNanos[6] = 0;
pipeProfileNanos[7] = 0;
pipeProfileNanos[8] = 0;
}
}
}

View File

@@ -22,6 +22,9 @@ import java.util.Arrays;
import java.util.Comparator;
import java.util.List;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.dataflow.DataChangeService;
import org.photonvision.common.dataflow.events.OutgoingUIEvent;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.pipeline.*;
@@ -48,7 +51,7 @@ public class PipelineManager {
* <br>
* Used only when switching from any of the built-in pipelines back to a user-created pipeline.
*/
private int lastPipelineIndex;
private int lastUserPipelineIdx;
/**
* Creates a PipelineManager with a DriverModePipeline, a Calibration3dPipeline, and all provided
@@ -141,7 +144,7 @@ public class PipelineManager {
*
* @return The currently active pipeline.
*/
public CVPipeline getCurrentUserPipeline() {
public CVPipeline getCurrentPipeline() {
if (currentPipelineIndex < 0) {
switch (currentPipelineIndex) {
case CAL_3D_INDEX:
@@ -151,23 +154,7 @@ public class PipelineManager {
}
}
var desiredPipelineSettings = userPipelineSettings.get(currentPipelineIndex);
// if (currentPipeline.getSettings().pipelineIndex !=
// desiredPipelineSettings.pipelineIndex) {
// switch (desiredPipelineSettings.pipelineType) {
// case Reflective:
// currentPipeline =
// new ReflectivePipeline((ReflectivePipelineSettings)
// desiredPipelineSettings);
// break;
// case ColoredShape:
// currentPipeline =
// new ColoredShapePipeline((ColoredShapePipelineSettings)
// desiredPipelineSettings);
// break;
// }
// }
// Just return the current user pipeline, we're not on aa built-in one
return currentUserPipeline;
}
@@ -186,20 +173,21 @@ public class PipelineManager {
* All externally accessible methods that intend to change the active pipeline MUST go through
* here to ensure all proper steps are taken.
*
* @param index Index of pipeline to be active
* @param newIndex Index of pipeline to be active
*/
private void setPipelineInternal(int index) {
if (index < 0) {
lastPipelineIndex = currentPipelineIndex;
private void setPipelineInternal(int newIndex) {
if (newIndex < 0 && currentPipelineIndex >= 0) {
// Transitioning to a built-in pipe, save off the current user one
lastUserPipelineIdx = currentPipelineIndex;
}
if (userPipelineSettings.size() - 1 < index) {
if (userPipelineSettings.size() - 1 < newIndex) {
logger.warn("User attempted to set index to non-existent pipeline!");
return;
}
currentPipelineIndex = index;
if (index >= 0) {
currentPipelineIndex = newIndex;
if (newIndex >= 0) {
var desiredPipelineSettings = userPipelineSettings.get(currentPipelineIndex);
switch (desiredPipelineSettings.pipelineType) {
case Reflective:
@@ -222,6 +210,11 @@ public class PipelineManager {
break;
}
}
DataChangeService.getInstance()
.publishEvent(
new OutgoingUIEvent<>(
"fullsettings", ConfigManager.getInstance().getConfig().toHashMap()));
}
/**
@@ -233,7 +226,7 @@ public class PipelineManager {
*/
public void setCalibrationMode(boolean wantsCalibration) {
if (!wantsCalibration) calibration3dPipeline.finishCalibration();
setPipelineInternal(wantsCalibration ? CAL_3D_INDEX : lastPipelineIndex);
setPipelineInternal(wantsCalibration ? CAL_3D_INDEX : lastUserPipelineIdx);
}
/**
@@ -244,7 +237,7 @@ public class PipelineManager {
* @param state True to enter driver mode, false to exit driver mode.
*/
public void setDriverMode(boolean state) {
setPipelineInternal(state ? DRIVERMODE_INDEX : lastPipelineIndex);
setPipelineInternal(state ? DRIVERMODE_INDEX : lastUserPipelineIdx);
}
/**

View File

@@ -120,7 +120,7 @@ public class VisionModule {
this.visionRunner =
new VisionRunner(
this.visionSource.getFrameProvider(),
this.pipelineManager::getCurrentUserPipeline,
this.pipelineManager::getCurrentPipeline,
this::consumeResult,
this.cameraQuirks);
this.streamRunnable = new StreamRunnable(new OutputStreamPipeline());
@@ -578,7 +578,7 @@ public class VisionModule {
}
public void setTargetModel(TargetModel targetModel) {
var settings = pipelineManager.getCurrentUserPipeline().getSettings();
var settings = pipelineManager.getCurrentPipeline().getSettings();
if (settings instanceof ReflectivePipelineSettings) {
((ReflectivePipelineSettings) settings).targetModel = targetModel;
saveAndBroadcastAll();

View File

@@ -59,7 +59,7 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber {
var propName = wsEvent.propertyName;
var newPropValue = wsEvent.data;
var currentSettings = parentModule.pipelineManager.getCurrentUserPipeline().getSettings();
var currentSettings = parentModule.pipelineManager.getCurrentPipeline().getSettings();
// special case for non-PipelineSetting changes
switch (propName) {