Skip to content

Commit

Permalink
renamed things for better reflection of what it actually is
Browse files Browse the repository at this point in the history
  • Loading branch information
gerth2 committed Jun 28, 2024
1 parent d46efd1 commit 8b4a2de
Show file tree
Hide file tree
Showing 21 changed files with 142 additions and 115 deletions.
12 changes: 6 additions & 6 deletions photon-client/src/components/cameras/CameraCalibrationCard.vue
Original file line number Diff line number Diff line change
Expand Up @@ -389,15 +389,15 @@ const setSelectedVideoFormat = (format: VideoFormat) => {
<v-row v-if="isCalibrating">
<v-col cols="12" class="pt-0">
<pv-slider
v-model="useCameraSettingsStore().currentPipelineSettings.cameraExposureUs"
v-model="useCameraSettingsStore().currentPipelineSettings.cameraExposureRaw"
:disabled="useCameraSettingsStore().currentCameraSettings.pipelineSettings.cameraAutoExposure"
label="Exposure (μS)"
tooltip="Directly controls how long the camera shutter remains open (in microseconds)"
:min="useCameraSettingsStore().minExposureUs"
:max="useCameraSettingsStore().maxExposureUs"
label="Exposure"
tooltip="Directly controls how long the camera shutter remains open. Units are dependant on the underlying driver."
:min="useCameraSettingsStore().minExposureRaw"
:max="useCameraSettingsStore().maxExposureRaw"
:slider-cols="8"
:step="1"
@input="(args) => useCameraSettingsStore().changeCurrentPipelineSetting({ cameraExposureUs: args }, false)"
@input="(args) => useCameraSettingsStore().changeCurrentPipelineSetting({ cameraExposureRaw: args }, false)"
/>
<pv-slider
v-model="useCameraSettingsStore().currentPipelineSettings.cameraBrightness"
Expand Down
12 changes: 6 additions & 6 deletions photon-client/src/components/dashboard/tabs/InputTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -74,15 +74,15 @@ const interactiveCols = computed(() =>
<template>
<div>
<pv-slider
v-model="useCameraSettingsStore().currentPipelineSettings.cameraExposureUs"
v-model="useCameraSettingsStore().currentPipelineSettings.cameraExposureRaw"
:disabled="useCameraSettingsStore().currentCameraSettings.pipelineSettings.cameraAutoExposure"
label="Exposure (μS)"
tooltip="Directly controls how long the camera shutter remains open (in microseconds)"
:min="useCameraSettingsStore().minExposureUs"
:max="useCameraSettingsStore().maxExposureUs"
label="Exposure"
tooltip="Directly controls how long the camera shutter remains open. Units are dependant on the underlying driver."
:min="useCameraSettingsStore().minExposureRaw"
:max="useCameraSettingsStore().maxExposureRaw"
:slider-cols="interactiveCols"
:step="1"
@input="(args) => useCameraSettingsStore().changeCurrentPipelineSetting({ cameraExposureUs: args }, false)"
@input="(args) => useCameraSettingsStore().changeCurrentPipelineSetting({ cameraExposureRaw: args }, false)"
/>
<pv-slider
v-model="useCameraSettingsStore().currentPipelineSettings.cameraBrightness"
Expand Down
12 changes: 6 additions & 6 deletions photon-client/src/stores/settings/CameraSettingsStore.ts
Original file line number Diff line number Diff line change
Expand Up @@ -69,11 +69,11 @@ export const useCameraSettingsStore = defineStore("cameraSettings", {
isCSICamera(): boolean {
return this.currentCameraSettings.isCSICamera;
},
minExposureUs(): number {
return this.currentCameraSettings.minExposureUs;
minExposureRaw(): number {
return this.currentCameraSettings.minExposureRaw;
},
maxExposureUs(): number {
return this.currentCameraSettings.maxExposureUs;
maxExposureRaw(): number {
return this.currentCameraSettings.maxExposureRaw;
}
},
actions: {
Expand Down Expand Up @@ -108,8 +108,8 @@ export const useCameraSettingsStore = defineStore("cameraSettings", {
})),
completeCalibrations: d.calibrations,
isCSICamera: d.isCSICamera,
minExposureUs: d.minExposureUs,
maxExposureUs: d.maxExposureUs,
minExposureRaw: d.minExposureRaw,
maxExposureRaw: d.maxExposureRaw,
pipelineNicknames: d.pipelineNicknames,
currentPipelineIndex: d.currentPipelineIndex,
pipelineSettings: d.currentPipelineSettings,
Expand Down
18 changes: 9 additions & 9 deletions photon-client/src/types/PipelineTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,9 @@ export interface PipelineSettings {
hueInverted: boolean;
outputShowMultipleTargets: boolean;
contourSortMode: number;
cameraExposureUs: number;
cameraMinExposureUs: number;
cameraMaxExposureUs: number;
cameraExposureRaw: number;
cameraMinexposureRaw: number;
cameraMaxexposureRaw: number;
offsetSinglePoint: { x: number; y: number };
cameraBrightness: number;
offsetDualPointAArea: number;
Expand Down Expand Up @@ -99,7 +99,7 @@ export type ConfigurablePipelineSettings = Partial<
// Omitted settings are changed for all pipeline types
export const DefaultPipelineSettings: Omit<
PipelineSettings,
"cameraGain" | "targetModel" | "ledMode" | "outputShowMultipleTargets" | "cameraExposureUs" | "pipelineType"
"cameraGain" | "targetModel" | "ledMode" | "outputShowMultipleTargets" | "cameraExposureRaw" | "pipelineType"
> = {
offsetRobotOffsetMode: RobotOffsetPointMode.None,
streamingFrameDivisor: 0,
Expand Down Expand Up @@ -153,7 +153,7 @@ export const DefaultReflectivePipelineSettings: ReflectivePipelineSettings = {
targetModel: TargetModel.InfiniteRechargeHighGoalOuter,
ledMode: true,
outputShowMultipleTargets: false,
cameraExposureUs: 6,
cameraExposureRaw: 6,
pipelineType: PipelineType.Reflective,

contourFilterRangeY: 2,
Expand Down Expand Up @@ -184,7 +184,7 @@ export const DefaultColoredShapePipelineSettings: ColoredShapePipelineSettings =
targetModel: TargetModel.InfiniteRechargeHighGoalOuter,
ledMode: true,
outputShowMultipleTargets: false,
cameraExposureUs: 20,
cameraExposureRaw: 20,
pipelineType: PipelineType.ColoredShape,

erode: false,
Expand Down Expand Up @@ -224,7 +224,7 @@ export const DefaultAprilTagPipelineSettings: AprilTagPipelineSettings = {
targetModel: TargetModel.AprilTag6p5in_36h11,
ledMode: false,
outputShowMultipleTargets: true,
cameraExposureUs: 20,
cameraExposureRaw: 20,
pipelineType: PipelineType.AprilTag,

hammingDist: 0,
Expand Down Expand Up @@ -266,7 +266,7 @@ export const DefaultArucoPipelineSettings: ArucoPipelineSettings = {
cameraGain: 75,
outputShowMultipleTargets: true,
targetModel: TargetModel.AprilTag6p5in_36h11,
cameraExposureUs: -1,
cameraExposureRaw: -1,
cameraAutoExposure: true,
ledMode: false,
pipelineType: PipelineType.Aruco,
Expand Down Expand Up @@ -301,7 +301,7 @@ export const DefaultObjectDetectionPipelineSettings: ObjectDetectionPipelineSett
targetModel: TargetModel.InfiniteRechargeHighGoalOuter,
ledMode: true,
outputShowMultipleTargets: false,
cameraExposureUs: 6,
cameraExposureRaw: 6,
confidence: 0.9,
nms: 0.45,
box_thresh: 0.25
Expand Down
8 changes: 4 additions & 4 deletions photon-client/src/types/SettingTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -190,8 +190,8 @@ export interface CameraSettings {
cameraQuirks: QuirkyCamera;
isCSICamera: boolean;

minExposureUs: number;
maxExposureUs: number;
minExposureRaw: number;
maxExposureRaw: number;
}

export interface CameraSettingsChangeRequest {
Expand Down Expand Up @@ -291,8 +291,8 @@ export const PlaceholderCameraSettings: CameraSettings = {
}
},
isCSICamera: false,
minExposureUs: 1,
maxExposureUs: 100
minExposureRaw: 1,
maxExposureRaw: 100
};

export enum CalibrationBoardTypes {
Expand Down
4 changes: 2 additions & 2 deletions photon-client/src/types/WebsocketDataTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,8 @@ export interface WebsocketCameraSettingsUpdate {
pipelineNicknames: string[];
videoFormatList: WebsocketVideoFormat;
cameraQuirks: QuirkyCamera;
minExposureUs: number;
maxExposureUs: number;
minExposureRaw: number;
maxExposureRaw: number;
}
export interface WebsocketNTUpdate {
connected: boolean;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ public static class UICameraConfiguration {
public boolean isFovConfigurable = true;
public QuirkyCamera cameraQuirks;
public boolean isCSICamera;
public double minExposureUs;
public double maxExposureUs;
public double minExposureRaw;
public double maxExposureRaw;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ public enum CameraQuirk {
Gain,
/** Only certain discrete exposure settings work */
LifeCamExposure,
/** Auto-Exposure property uses 1/0, rather than 3/1 */
OneZeroAutoExposure,
/** Cap at 100FPS for high-bandwidth cameras */
FPSCap100,
/** Separate red/blue gain controls available */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ private static class FileSourceSettables extends VisionSourceSettables {
}

@Override
public void setExposureUs(double exposureUs) {}
public void setexposureRaw(double exposureRaw) {}

public void setAutoExposure(boolean cameraAutoExposure) {}

Expand All @@ -124,12 +124,12 @@ public HashMap<Integer, VideoMode> getAllVideoModes() {
}

@Override
public double getMinExposureUs() {
public double getMinexposureRaw() {
return 1f;
}

@Override
public double getMaxExposureUs() {
public double getMaxexposureRaw() {
return 100f;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,20 +123,20 @@ public void setAutoExposure(boolean cameraAutoExposure) {
}

@Override
public void setExposureUs(double exposureUs) {
if (exposureUs < 0.0 || lastAutoExposureActive) {
public void setexposureRaw(double exposureRaw) {
if (exposureRaw < 0.0 || lastAutoExposureActive) {
// Auto-exposure is active right now, don't set anything.
return;
}

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

// 80,000 uS seems like an exposure value that will be greater than ever needed while giving
// enough control over exposure.
exposureUs = MathUtils.limit(exposureUs, minExposure, maxExposure);
exposureRaw = MathUtils.limit(exposureRaw, minExposure, maxExposure);

var success = LibCameraJNI.setExposure(r_ptr, (int) exposureUs);
var success = LibCameraJNI.setExposure(r_ptr, (int) exposureRaw);
if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera exposure");
}

Expand Down Expand Up @@ -227,7 +227,7 @@ protected void setVideoModeInternal(VideoMode videoMode) {

// We don't store last settings on the native side, and when you change video mode these get
// reset on MMAL's end
setExposureUs(lastManualExposure);
setexposureRaw(lastManualExposure);
setAutoExposure(lastAutoExposureActive);
setBrightness(lastBrightness);
setGain(lastGain);
Expand All @@ -248,12 +248,12 @@ public LibCameraJNI.SensorModel getModel() {
}

@Override
public double getMinExposureUs() {
public double getMinexposureRaw() {
return this.minExposure;
}

@Override
public double getMaxExposureUs() {
public double getMaxexposureRaw() {
return this.maxExposure;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -28,30 +28,43 @@
public class QuirkyCamera {
private static final List<QuirkyCamera> quirkyCameras =
List.of(
// Chris's older generic "Logitec HD Webcam"
new QuirkyCamera(
0x9331,
0x5A3,
CameraQuirk.CompletelyBroken), // Chris's older generic "Logitec HD Webcam"
new QuirkyCamera(0x825, 0x46D, CameraQuirk.CompletelyBroken), // Logitec C270
CameraQuirk.CompletelyBroken),
// Logitec C270
new QuirkyCamera(0x825, 0x46D, CameraQuirk.CompletelyBroken),
// A laptop internal camera someone found broken
new QuirkyCamera(
0x0bda,
0x5510,
CameraQuirk.CompletelyBroken), // A laptop internal camera someone found broken
CameraQuirk.CompletelyBroken),
// SnapCamera on Windows
new QuirkyCamera(
-1, -1, "Snap Camera", CameraQuirk.CompletelyBroken), // SnapCamera on Windows
-1, -1, "Snap Camera", CameraQuirk.CompletelyBroken),
// Mac Facetime Camera shared into Windows in Bootcamp
new QuirkyCamera(
-1,
-1,
"FaceTime HD Camera",
CameraQuirk.CompletelyBroken), // Mac Facetime Camera shared into Windows in Bootcamp
CameraQuirk.CompletelyBroken),
// Microsoft Lifecam
new QuirkyCamera(
-1, -1, "LifeCam HD-3000", CameraQuirk.LifeCamExposure), // Microsoft Lifecam
-1, -1, "LifeCam HD-3000", CameraQuirk.LifeCamExposure),
// Microsoft Lifecam
new QuirkyCamera(
-1, -1, "LifeCam Cinema (TM)", CameraQuirk.LifeCamExposure), // Microsoft Lifecam
new QuirkyCamera(0x2000, 0x1415, CameraQuirk.Gain, CameraQuirk.FPSCap100), // PS3Eye
new QuirkyCamera(0x85B, 0x46D, CameraQuirk.AdjustableFocus), // Logitech C925-e
// Generic arducam. Since OV2311 can't be differentiated at first boot, apply stickyFPS to
// the generic case, too
-1, -1, "LifeCam Cinema (TM)", CameraQuirk.LifeCamExposure),
// PS3Eye
new QuirkyCamera(0x1415,
0x2000,
CameraQuirk.Gain,
CameraQuirk.FPSCap100,
CameraQuirk.OneZeroAutoExposure),
// Logitech C925-e
new QuirkyCamera(0x85B, 0x46D, CameraQuirk.AdjustableFocus),
// Generic arducam. Since OV2311 can't be differentiated
// at first boot, apply stickyFPS to the generic case, too
new QuirkyCamera(
0x0c45,
0x6366,
Expand Down
Loading

0 comments on commit 8b4a2de

Please sign in to comment.