Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Check all new prop names not just exposure time #1080

Merged
merged 19 commits into from
Jan 6, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 47 additions & 9 deletions photon-client/src/components/cameras/CameraSettingsCard.vue
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,13 @@ import PvSelect from "@/components/common/pv-select.vue";
import PvNumberInput from "@/components/common/pv-number-input.vue";
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
import { useStateStore } from "@/stores/StateStore";
import { ref, watchEffect } from "vue";
import { computed, ref, watchEffect } from "vue";

const currentFov = ref();

const saveCameraSettings = () => {
useCameraSettingsStore()
.updateCameraSettings({ fov: currentFov.value }, false)
.updateCameraSettings({ fov: currentFov.value, quirksToChange: quirksToChange.value }, false)
.then((response) => {
useCameraSettingsStore().currentCameraSettings.fov.value = currentFov.value;
useStateStore().showSnackbarMessage({
Expand Down Expand Up @@ -41,6 +41,43 @@ const saveCameraSettings = () => {
watchEffect(() => {
currentFov.value = useCameraSettingsStore().currentCameraSettings.fov.value;
});

const quirksToChange = ref({
ArduOV9281: false,
ArduOV2311: false
});

let arducams = ["N/A", "OV9281", "OV2311"];

const arducamModel = computed({
get() {
const quirks = useCameraSettingsStore().currentCameraSettings.cameraQuirks.quirks;

if (quirks.ArduOV9281) {
return 1;
} else if (quirks.ArduOV2311) {
return 2;
}
return 0;
},
set(value) {
if (value === 1) {
quirksToChange.value.ArduOV9281 = true;
quirksToChange.value.ArduOV2311 = false;
} else if (value === 2) {
quirksToChange.value.ArduOV9281 = false;
quirksToChange.value.ArduOV2311 = true;
} else {
quirksToChange.value.ArduOV9281 = false;
quirksToChange.value.ArduOV2311 = false;
}
}
});

const isArducam = () => {
const settings = useCameraSettingsStore().currentCameraSettings;
return settings.cameraQuirks.quirks.ArduCamCamera;
};
</script>

<template>
Expand Down Expand Up @@ -70,14 +107,15 @@ watchEffect(() => {
:disabled="useCameraSettingsStore().currentCameraSettings.fov.managedByVendor"
:label-cols="4"
/>
<pv-select
v-model="arducamModel"
label="Arducam Model"
:disabled="!isArducam()"
:items="arducams"
:select-cols="8"
/>
<br />
<v-btn
style="margin-top: 10px"
small
color="secondary"
:disabled="currentFov === useCameraSettingsStore().currentCameraSettings.fov.value"
@click="saveCameraSettings"
>
<v-btn style="margin-top: 10px" small color="secondary" @click="saveCameraSettings">
<v-icon left> mdi-content-save </v-icon>
Save Changes
</v-btn>
Expand Down
3 changes: 2 additions & 1 deletion photon-client/src/stores/settings/CameraSettingsStore.ts
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,8 @@ export const useCameraSettingsStore = defineStore("cameraSettings", {
isCSICamera: d.isCSICamera,
pipelineNicknames: d.pipelineNicknames,
currentPipelineIndex: d.currentPipelineIndex,
pipelineSettings: d.currentPipelineSettings
pipelineSettings: d.currentPipelineSettings,
cameraQuirks: d.cameraQuirks
}));
},
/**
Expand Down
43 changes: 42 additions & 1 deletion photon-client/src/types/SettingTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,27 @@ export interface CameraCalibrationResult {

export interface ConfigurableCameraSettings {
fov: number;
// Need map of (quirk name string) -> boolean
quirksToChange: object;
}

export interface QuirkyCamera {
baseName: string;
usbVid: number;
usbPid: number;
displayName: string;
quirks: {
AWBGain: boolean;
AdjustableFocus: boolean;
ArduOV9281: boolean;
ArduOV2311: boolean;
ArduCamCamera: boolean;
CompletelyBroken: boolean;
FPSCap100: boolean;
Gain: boolean;
PiCam: boolean;
StickyFPS: boolean;
};
}

export interface CameraSettings {
Expand All @@ -159,6 +180,8 @@ export interface CameraSettings {
currentPipelineIndex: number;
pipelineNicknames: string[];
pipelineSettings: ActivePipelineSettings;

cameraQuirks: QuirkyCamera;
isCSICamera: boolean;
}

Expand Down Expand Up @@ -233,7 +256,25 @@ export const PlaceholderCameraSettings: CameraSettings = {
lastPipelineIndex: 0,
currentPipelineIndex: 0,
pipelineSettings: DefaultAprilTagPipelineSettings,
isCSICamera: false
cameraQuirks: {
displayName: "Blank 1",
baseName: "Blank 2",
usbVid: -1,
usbPid: -1,
quirks: {
AWBGain: false,
AdjustableFocus: false,
ArduOV9281: false,
ArduOV2311: false,
ArduCamCamera: false,
CompletelyBroken: false,
FPSCap100: false,
Gain: false,
PiCam: false,
StickyFPS: false,
},
},
isCSICamera: false,
};

export enum CalibrationBoardTypes {
Expand Down
4 changes: 3 additions & 1 deletion photon-client/src/types/WebsocketDataTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,8 @@ import type {
LightingSettings,
LogLevel,
MetricData,
NetworkSettings
NetworkSettings,
QuirkyCamera
} from "@/types/SettingTypes";
import type { ActivePipelineSettings } from "@/types/PipelineTypes";
import type { AprilTagFieldLayout, PipelineResult } from "@/types/PhotonTrackingTypes";
Expand Down Expand Up @@ -56,6 +57,7 @@ export interface WebsocketCameraSettingsUpdate {
outputStreamPort: number;
pipelineNicknames: string[];
videoFormatList: WebsocketVideoFormat;
cameraQuirks: QuirkyCamera;
}
export interface WebsocketNTUpdate {
connected: boolean;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.camera.CameraType;
import org.photonvision.vision.camera.QuirkyCamera;
import org.photonvision.vision.pipeline.CVPipelineSettings;
import org.photonvision.vision.pipeline.DriverModePipelineSettings;
import org.photonvision.vision.processes.PipelineManager;
Expand All @@ -46,6 +47,8 @@ public class CameraConfiguration {
/** Can be either path (ex /dev/videoX) or index (ex 1). */
public String path = "";

public QuirkyCamera cameraQuirks;

@JsonIgnore public String[] otherPaths = {};

public CameraType cameraType = CameraType.UsbCamera;
Expand Down Expand Up @@ -93,6 +96,7 @@ public CameraConfiguration(
@JsonProperty("FOV") double FOV,
@JsonProperty("path") String path,
@JsonProperty("cameraType") CameraType cameraType,
@JsonProperty("cameraQuirks") QuirkyCamera cameraQuirks,
@JsonProperty("calibration") List<CameraCalibrationCoefficients> calibrations,
@JsonProperty("currentPipelineIndex") int currentPipelineIndex) {
this.baseName = baseName;
Expand All @@ -101,6 +105,7 @@ public CameraConfiguration(
this.FOV = FOV;
this.path = path;
this.cameraType = cameraType;
this.cameraQuirks = cameraQuirks;
this.calibrations = calibrations != null ? calibrations : new ArrayList<>();
this.currentPipelineIndex = currentPipelineIndex;

Expand Down Expand Up @@ -165,6 +170,8 @@ public String toString() {
+ Arrays.toString(otherPaths)
+ ", cameraType="
+ cameraType
+ ", cameraQuirks="
+ cameraQuirks
+ ", FOV="
+ FOV
+ ", calibrations="
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
import org.photonvision.mrcal.MrCalJNILoader;
import org.photonvision.raspi.LibCameraJNILoader;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.camera.QuirkyCamera;
import org.photonvision.vision.processes.VisionModule;
import org.photonvision.vision.processes.VisionModuleManager;
import org.photonvision.vision.processes.VisionSource;
Expand Down Expand Up @@ -178,6 +179,7 @@ public static class UICameraConfiguration {
public int inputStreamPort;
public List<CameraCalibrationCoefficients> calibrations;
public boolean isFovConfigurable = true;
public QuirkyCamera cameraQuirks;
public boolean isCSICamera;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -32,4 +32,13 @@ public enum CameraQuirk {
AdjustableFocus,
/** Changing FPS repeatedly with small delay does not work correctly */
StickyFPS,
/** Camera is an arducam. This means it shares VID/PID with other arducams (ew) */
ArduCamCamera,
/**
* Camera is an arducam ov9281 which has a funky exposure issue where it is defined in v4l as
* 1-5000 instead of 1-75
*/
ArduOV9281,
/** Dummy quirk to tell OV2311 from OV9281 */
ArduOV2311,
}
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

package org.photonvision.vision.camera;

import com.fasterxml.jackson.annotation.JsonCreator;
import com.fasterxml.jackson.annotation.JsonProperty;
import java.util.ArrayList;
import java.util.Arrays;
import java.util.HashMap;
Expand Down Expand Up @@ -47,8 +49,32 @@ public class QuirkyCamera {
-1, -1, "mmal service 16.1", CameraQuirk.PiCam), // PiCam (via V4L2, not zerocopy)
new QuirkyCamera(-1, -1, "unicam", CameraQuirk.PiCam), // PiCam (via V4L2, not zerocopy)
new QuirkyCamera(0x85B, 0x46D, CameraQuirk.AdjustableFocus), // Logitech C925-e
new QuirkyCamera(0x6366, 0x0c45, CameraQuirk.StickyFPS) // Arducam OV2311
);
// Generic arducam. Since OV2311 can't be differentiated at first boot, apply stickyFPS to
// the generic case, too
new QuirkyCamera(
0x0c45,
0x6366,
"",
"Arducam Generic",
CameraQuirk.ArduCamCamera,
CameraQuirk.StickyFPS),
// Arducam OV2311
new QuirkyCamera(
0x0c45,
0x6366,
"OV2311",
"OV2311",
CameraQuirk.ArduCamCamera,
CameraQuirk.ArduOV2311,
CameraQuirk.StickyFPS),
// Arducam OV9281
new QuirkyCamera(
0x0c45,
0x6366,
"OV9281",
"OV9281",
CameraQuirk.ArduCamCamera,
CameraQuirk.ArduOV9281));

public static final QuirkyCamera DefaultCamera = new QuirkyCamera(0, 0, "");
public static final QuirkyCamera ZeroCopyPiCamera =
Expand All @@ -60,9 +86,19 @@ public class QuirkyCamera {
CameraQuirk.Gain,
CameraQuirk.AWBGain); // PiCam (special zerocopy version)

@JsonProperty("baseName")
public final String baseName;

@JsonProperty("usbVid")
public final int usbVid;

@JsonProperty("usbPid")
public final int usbPid;

@JsonProperty("displayName")
public final String displayName;

@JsonProperty("quirks")
public final HashMap<CameraQuirk, Boolean> quirks;

/**
Expand All @@ -85,9 +121,24 @@ private QuirkyCamera(int usbVid, int usbPid, CameraQuirk... quirks) {
* @param quirks Camera quirks
*/
private QuirkyCamera(int usbVid, int usbPid, String baseName, CameraQuirk... quirks) {
this(usbVid, usbPid, baseName, "", quirks);
}

/**
* Creates a QuirkyCamera that matches by USB VID/PID and name
*
* @param usbVid USB VID of camera
* @param usbPid USB PID of camera
* @param baseName CSCore name of camera
* @param displayName Human-friendly quicky camera name
* @param quirks Camera quirks
*/
private QuirkyCamera(
int usbVid, int usbPid, String baseName, String displayName, CameraQuirk... quirks) {
this.usbVid = usbVid;
this.usbPid = usbPid;
this.baseName = baseName;
this.displayName = displayName;

this.quirks = new HashMap<>();
for (var q : quirks) {
Expand All @@ -98,6 +149,20 @@ private QuirkyCamera(int usbVid, int usbPid, String baseName, CameraQuirk... qui
}
}

@JsonCreator
public QuirkyCamera(
@JsonProperty("baseName") String baseName,
@JsonProperty("usbVid") int usbVid,
@JsonProperty("usbPid") int usbPid,
@JsonProperty("displayName") String displayName,
@JsonProperty("quirks") HashMap<CameraQuirk, Boolean> quirks) {
this.baseName = baseName;
this.usbPid = usbPid;
this.usbVid = usbVid;
this.quirks = quirks;
this.displayName = displayName;
}

public boolean hasQuirk(CameraQuirk quirk) {
return quirks.get(quirk);
}
Expand Down Expand Up @@ -144,8 +209,39 @@ public boolean equals(Object o) {
&& Objects.equals(quirks, that.quirks);
}

@Override
public String toString() {
String ret =
"QuirkyCamera [baseName="
+ baseName
+ ", displayName="
+ displayName
+ ", usbVid="
+ usbVid
+ ", usbPid="
+ usbPid
+ ", quirks="
+ quirks.toString()
+ "]";
return ret;
}

@Override
public int hashCode() {
return Objects.hash(usbVid, usbPid, baseName, quirks);
}

/**
* Add/remove quirks from the camera we're controlling
*
* @param quirksToChange map of true/false for quirks we should change
*/
public void updateQuirks(HashMap<CameraQuirk, Boolean> quirksToChange) {
for (var q : quirksToChange.entrySet()) {
var quirk = q.getKey();
var hasQuirk = q.getValue();

this.quirks.put(quirk, hasQuirk);
}
}
}
Loading