mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
Compare commits
33 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
5dc70e4d3f | ||
|
|
5597f5acd9 | ||
|
|
fae3116951 | ||
|
|
def37b92ba | ||
|
|
5b878fe3a3 | ||
|
|
d9c2a382f1 | ||
|
|
e125632960 | ||
|
|
d8f82bf9ee | ||
|
|
587ac478f4 | ||
|
|
bad676f67c | ||
|
|
71128d1569 | ||
|
|
7cec141341 | ||
|
|
ec66645667 | ||
|
|
39aaa34520 | ||
|
|
4a3200d0c0 | ||
|
|
01dc7ea5ce | ||
|
|
2a9502be3d | ||
|
|
39216db143 | ||
|
|
428f926ac2 | ||
|
|
4efeb3d412 | ||
|
|
6a2d83e19b | ||
|
|
1c0d92641f | ||
|
|
9653c46bdb | ||
|
|
3738e7821b | ||
|
|
0eb0a4e3c5 | ||
|
|
7666f152bb | ||
|
|
45a39f6609 | ||
|
|
bc55218739 | ||
|
|
e616d93d59 | ||
|
|
5851509a9e | ||
|
|
ea1b701ba7 | ||
|
|
62112cd2fd | ||
|
|
c7508fea46 |
81
.github/workflows/build.yml
vendored
81
.github/workflows/build.yml
vendored
@@ -260,6 +260,83 @@ jobs:
|
||||
with:
|
||||
name: jar-${{ matrix.artifact-name }}
|
||||
path: photon-server/build/libs
|
||||
|
||||
run-smoketest-native:
|
||||
needs: [build-package]
|
||||
|
||||
strategy:
|
||||
fail-fast: false
|
||||
matrix:
|
||||
include:
|
||||
- os: ubuntu-latest
|
||||
artifact-name: jar-Linux
|
||||
extraOpts: -Djdk.lang.Process.launchMechanism=vfork
|
||||
- os: windows-latest
|
||||
artifact-name: jar-Win64
|
||||
extraOpts: ""
|
||||
- os: macos-latest
|
||||
artifact-name: jar-macOS
|
||||
architecture: x64
|
||||
|
||||
runs-on: ${{ matrix.os }}
|
||||
|
||||
steps:
|
||||
- name: Install Java 17
|
||||
uses: actions/setup-java@v4
|
||||
with:
|
||||
java-version: 17
|
||||
distribution: temurin
|
||||
- uses: actions/download-artifact@v4
|
||||
with:
|
||||
name: ${{ matrix.artifact-name }}
|
||||
# On linux, install mrcal packages
|
||||
- run: |
|
||||
sudo apt-get update
|
||||
sudo apt-get install --yes libcholmod3 liblapack3 libsuitesparseconfig5
|
||||
if: ${{ (matrix.os) == 'ubuntu-latest' }}
|
||||
# and actually run the jar
|
||||
- run: java -jar ${{ matrix.extraOpts }} *.jar --smoketest
|
||||
if: ${{ (matrix.os) != 'windows-latest' }}
|
||||
- run: ls *.jar | %{ Write-Host "Running $($_.Name)"; Start-Process "java" -ArgumentList "-jar `"$($_.FullName)`" --smoketest" -NoNewWindow -Wait; break }
|
||||
if: ${{ (matrix.os) == 'windows-latest' }}
|
||||
|
||||
run-smoketest-chroot:
|
||||
needs: [build-package]
|
||||
|
||||
strategy:
|
||||
fail-fast: false
|
||||
matrix:
|
||||
include:
|
||||
- os: ubuntu-latest
|
||||
artifact-name: LinuxArm64
|
||||
image_suffix: RaspberryPi
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.4/photonvision_raspi.img.xz
|
||||
cpu: cortex-a7
|
||||
image_additional_mb: 0
|
||||
extraOpts: -Djdk.lang.Process.launchMechanism=vfork
|
||||
|
||||
runs-on: ${{ matrix.os }}
|
||||
name: smoketest-${{ matrix.image_suffix }}
|
||||
|
||||
steps:
|
||||
- uses: actions/download-artifact@v4
|
||||
with:
|
||||
name: jar-${{ matrix.artifact-name }}
|
||||
|
||||
- uses: pguyot/arm-runner-action@v2
|
||||
name: Run photon smoketest
|
||||
id: generate_image
|
||||
with:
|
||||
base_image: ${{ matrix.image_url }}
|
||||
image_additional_mb: ${{ matrix.image_additional_mb }}
|
||||
optimize_image: yes
|
||||
cpu: ${{ matrix.cpu }}
|
||||
# We do _not_ wanna copy photon into the image. Bind mount instead
|
||||
bind_mount_repository: true
|
||||
# our image better have java installed already
|
||||
commands: |
|
||||
java -jar ${{ matrix.extraOpts }} *.jar --smoketest
|
||||
|
||||
build-image:
|
||||
needs: [build-package]
|
||||
|
||||
@@ -290,13 +367,13 @@ jobs:
|
||||
- os: ubuntu-latest
|
||||
artifact-name: LinuxArm64
|
||||
image_suffix: orangepi5
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.6/photonvision_opi5.img.xz
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.10/photonvision_opi5.img.xz
|
||||
cpu: cortex-a8
|
||||
image_additional_mb: 4096
|
||||
- os: ubuntu-latest
|
||||
artifact-name: LinuxArm64
|
||||
image_suffix: orangepi5plus
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.6/photonvision_opi5plus.img.xz
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.10/photonvision_opi5plus.img.xz
|
||||
cpu: cortex-a8
|
||||
image_additional_mb: 4096
|
||||
|
||||
|
||||
22
.github/workflows/documentation.yml
vendored
22
.github/workflows/documentation.yml
vendored
@@ -68,10 +68,6 @@ jobs:
|
||||
release:
|
||||
needs: [build-client, run_docs]
|
||||
|
||||
environment:
|
||||
name: github-pages
|
||||
url: ${{ steps.deployment.outputs.page_url }}
|
||||
|
||||
runs-on: ubuntu-22.04
|
||||
steps:
|
||||
|
||||
@@ -79,14 +75,12 @@ jobs:
|
||||
- uses: actions/download-artifact@v4
|
||||
|
||||
- run: find .
|
||||
|
||||
- name: Setup Pages
|
||||
uses: actions/configure-pages@v4
|
||||
- name: Upload artifact
|
||||
uses: actions/upload-pages-artifact@v3
|
||||
- name: copy file via ssh password
|
||||
uses: appleboy/scp-action@v0.1.7
|
||||
with:
|
||||
# Upload entire repository
|
||||
path: '.'
|
||||
- name: Deploy to GitHub Pages
|
||||
id: deployment
|
||||
uses: actions/deploy-pages@v4
|
||||
host: ${{ secrets.WEBMASTER_SSH_HOST }}
|
||||
username: ${{ secrets.WEBMASTER_SSH_USERNAME }}
|
||||
password: ${{ secrets.WEBMASTER_SSH_KEY }}
|
||||
port: ${{ secrets.WEBMASTER_SSH_PORT }}
|
||||
source: "*"
|
||||
target: /var/www/html/photonvision-docs/
|
||||
|
||||
@@ -4,7 +4,7 @@ plugins {
|
||||
id "com.diffplug.spotless" version "6.24.0"
|
||||
id "edu.wpi.first.NativeUtils" version "2024.6.1" apply false
|
||||
id "edu.wpi.first.wpilib.repositories.WPILibRepositoriesPlugin" version "2020.2"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
id 'edu.wpi.first.WpilibTools' version '1.3.0'
|
||||
id 'com.google.protobuf' version '0.9.4' apply false
|
||||
}
|
||||
@@ -24,15 +24,15 @@ allprojects {
|
||||
apply from: "versioningHelper.gradle"
|
||||
|
||||
ext {
|
||||
wpilibVersion = "2024.2.1"
|
||||
wpilibVersion = "2024.3.2"
|
||||
wpimathVersion = wpilibVersion
|
||||
openCVversion = "4.8.0-2"
|
||||
joglVersion = "2.4.0-rc-20200307"
|
||||
javalinVersion = "5.6.2"
|
||||
photonGlDriverLibVersion = "dev-v2023.1.0-9-g75fc678"
|
||||
rknnVersion = "dev-v2024.0.0-30-g001b5ec"
|
||||
rknnVersion = "dev-v2024.0.0-64-gc0836a6"
|
||||
frcYear = "2024"
|
||||
mrcalVersion = "dev-v2024.0.0-7-gc976aaa";
|
||||
mrcalVersion = "dev-v2024.0.0-18-gb903a09";
|
||||
|
||||
|
||||
pubVersion = versionString
|
||||
|
||||
@@ -162,9 +162,9 @@ def __convert_cal_to_mrcal_cameramodel(
|
||||
"indices_point_camintrinsics_camextrinsics": None,
|
||||
"lensmodel": model,
|
||||
"imagersizes": np.array([imagersize], dtype=np.int32),
|
||||
"calobject_warp": np.array(cal.calobjectWarp)
|
||||
if len(cal.calobjectWarp) > 0
|
||||
else None,
|
||||
"calobject_warp": (
|
||||
np.array(cal.calobjectWarp) if len(cal.calobjectWarp) > 0 else None
|
||||
),
|
||||
# We always do all the things
|
||||
"do_optimize_intrinsics_core": True,
|
||||
"do_optimize_intrinsics_distortions": True,
|
||||
|
||||
@@ -25,15 +25,10 @@ const getUniqueVideoFormatsByResolution = (): VideoFormat[] => {
|
||||
|
||||
const calib = useCameraSettingsStore().getCalibrationCoeffs(format.resolution);
|
||||
if (calib !== undefined) {
|
||||
// Is this the right formula for RMS error? who knows! not me!
|
||||
const perViewSumSquareReprojectionError = calib.observations.flatMap((it) =>
|
||||
it.reprojectionErrors.flatMap((it2) => [it2.x, it2.y])
|
||||
);
|
||||
// For each error, square it, sum the squares, and divide by total points N
|
||||
format.mean = Math.sqrt(
|
||||
perViewSumSquareReprojectionError.map((it) => Math.pow(it, 2)).reduce((a, b) => a + b, 0) /
|
||||
perViewSumSquareReprojectionError.length
|
||||
);
|
||||
if (calib.meanErrors.length)
|
||||
format.mean = calib.meanErrors.reduce((a, b) => a + b, 0) / calib.meanErrors.length;
|
||||
else format.mean = NaN;
|
||||
|
||||
format.horizontalFOV =
|
||||
2 * Math.atan2(format.resolution.width / 2, calib.cameraIntrinsics.data[0]) * (180 / Math.PI);
|
||||
@@ -109,7 +104,7 @@ const downloadCalibBoard = () => {
|
||||
const yPos = chessboardStartY + squareY * squareSizeIn.value;
|
||||
|
||||
// Only draw the odd squares to create the chessboard pattern
|
||||
if ((xPos + yPos + 0.25) % 2 === 0) {
|
||||
if (squareY % 2 != squareX % 2) {
|
||||
doc.rect(xPos, yPos, squareSizeIn.value, squareSizeIn.value, "F");
|
||||
}
|
||||
}
|
||||
@@ -263,7 +258,7 @@ const setSelectedVideoFormat = (format: VideoFormat) => {
|
||||
>
|
||||
<td>{{ getResolutionString(value.resolution) }}</td>
|
||||
<td>
|
||||
{{ value.mean !== undefined ? (isNaN(value.mean) ? "NaN" : value.mean.toFixed(2) + "px") : "-" }}
|
||||
{{ value.mean !== undefined ? (isNaN(value.mean) ? "Unknown" : value.mean.toFixed(2) + "px") : "-" }}
|
||||
</td>
|
||||
<td>{{ value.horizontalFOV !== undefined ? value.horizontalFOV.toFixed(2) + "°" : "-" }}</td>
|
||||
<td>{{ value.verticalFOV !== undefined ? value.verticalFOV.toFixed(2) + "°" : "-" }}</td>
|
||||
|
||||
@@ -1,51 +1,19 @@
|
||||
<script setup lang="ts">
|
||||
import type { BoardObservation, CameraCalibrationResult, VideoFormat } from "@/types/SettingTypes";
|
||||
import type { CameraCalibrationResult, VideoFormat } from "@/types/SettingTypes";
|
||||
import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore";
|
||||
import { useStateStore } from "@/stores/StateStore";
|
||||
import { ref } from "vue";
|
||||
import loadingImage from "@/assets/images/loading.svg";
|
||||
import { computed, inject, ref } from "vue";
|
||||
import { getResolutionString, parseJsonFile } from "@/lib/PhotonUtils";
|
||||
|
||||
const props = defineProps<{
|
||||
videoFormat: VideoFormat;
|
||||
}>();
|
||||
|
||||
const getMeanFromView = (o: BoardObservation) => {
|
||||
// Is this the right formula for RMS error? who knows! not me!
|
||||
const perViewSumSquareReprojectionError = o.reprojectionErrors.flatMap((it2) => [it2.x, it2.y]);
|
||||
|
||||
// For each error, square it, sum the squares, and divide by total points N
|
||||
return Math.sqrt(
|
||||
perViewSumSquareReprojectionError.map((it) => Math.pow(it, 2)).reduce((a, b) => a + b, 0) /
|
||||
perViewSumSquareReprojectionError.length
|
||||
);
|
||||
const exportCalibration = ref();
|
||||
const openExportCalibrationPrompt = () => {
|
||||
exportCalibration.value.click();
|
||||
};
|
||||
|
||||
// Import and export functions
|
||||
const downloadCalibration = () => {
|
||||
const calibData = useCameraSettingsStore().getCalibrationCoeffs(props.videoFormat.resolution);
|
||||
if (calibData === undefined) {
|
||||
useStateStore().showSnackbarMessage({
|
||||
color: "error",
|
||||
message:
|
||||
"Calibration data isn't available for the requested resolution, please calibrate the requested resolution first"
|
||||
});
|
||||
return;
|
||||
}
|
||||
|
||||
const camUniqueName = useCameraSettingsStore().currentCameraSettings.uniqueName;
|
||||
const filename = `photon_calibration_${camUniqueName}_${calibData.resolution.width}x${calibData.resolution.height}.json`;
|
||||
const fileData = JSON.stringify(calibData);
|
||||
|
||||
const element = document.createElement("a");
|
||||
element.style.display = "none";
|
||||
element.setAttribute("href", "data:text/plain;charset=utf-8," + encodeURIComponent(fileData));
|
||||
element.setAttribute("download", filename);
|
||||
|
||||
document.body.appendChild(element);
|
||||
element.click();
|
||||
document.body.removeChild(element);
|
||||
};
|
||||
const importCalibrationFromPhotonJson = ref();
|
||||
const openUploadPhotonCalibJsonPrompt = () => {
|
||||
importCalibrationFromPhotonJson.value.click();
|
||||
@@ -97,19 +65,28 @@ const importCalibration = async () => {
|
||||
};
|
||||
|
||||
interface ObservationDetails {
|
||||
snapshotSrc: any;
|
||||
mean: number;
|
||||
index: number;
|
||||
}
|
||||
|
||||
const currentCalibrationCoeffs = computed<CameraCalibrationResult | undefined>(() =>
|
||||
useCameraSettingsStore().getCalibrationCoeffs(props.videoFormat.resolution)
|
||||
);
|
||||
|
||||
const getObservationDetails = (): ObservationDetails[] | undefined => {
|
||||
return useCameraSettingsStore()
|
||||
.getCalibrationCoeffs(props.videoFormat.resolution)
|
||||
?.observations.map((o, i) => ({
|
||||
index: i,
|
||||
mean: parseFloat(getMeanFromView(o).toFixed(2)),
|
||||
snapshotSrc: o.includeObservationInCalibration ? "data:image/png;base64," + o.snapshotData.data : loadingImage
|
||||
}));
|
||||
const coefficients = currentCalibrationCoeffs.value;
|
||||
|
||||
return coefficients?.meanErrors.map((m, i) => ({
|
||||
index: i,
|
||||
mean: parseFloat(m.toFixed(2))
|
||||
}));
|
||||
};
|
||||
|
||||
const exportCalibrationURL = computed<string>(() =>
|
||||
useCameraSettingsStore().getCalJSONUrl(inject("backendHost") as string, props.videoFormat.resolution)
|
||||
);
|
||||
const calibrationImageURL = (index: number) =>
|
||||
useCameraSettingsStore().getCalImageUrl(inject<string>("backendHost") as string, props.videoFormat.resolution, index);
|
||||
</script>
|
||||
|
||||
<template>
|
||||
@@ -140,19 +117,22 @@ const getObservationDetails = (): ObservationDetails[] | undefined => {
|
||||
<v-btn
|
||||
color="secondary"
|
||||
class="mt-4"
|
||||
:disabled="useCameraSettingsStore().getCalibrationCoeffs(props.videoFormat.resolution) === undefined"
|
||||
:disabled="!currentCalibrationCoeffs"
|
||||
style="width: 100%"
|
||||
@click="downloadCalibration"
|
||||
@click="openExportCalibrationPrompt"
|
||||
>
|
||||
<v-icon left>mdi-export</v-icon>
|
||||
<span>Export</span>
|
||||
</v-btn>
|
||||
<a
|
||||
ref="exportCalibration"
|
||||
style="color: black; text-decoration: none; display: none"
|
||||
:href="exportCalibrationURL"
|
||||
target="_blank"
|
||||
/>
|
||||
</v-col>
|
||||
</v-row>
|
||||
<v-row
|
||||
v-if="useCameraSettingsStore().getCalibrationCoeffs(props.videoFormat.resolution) !== undefined"
|
||||
class="pt-2"
|
||||
>
|
||||
<v-row v-if="currentCalibrationCoeffs" class="pt-2">
|
||||
<v-card-subtitle>Calibration Details</v-card-subtitle>
|
||||
<v-simple-table dense style="width: 100%" class="pl-2 pr-2">
|
||||
<template #default>
|
||||
@@ -231,7 +211,9 @@ const getObservationDetails = (): ObservationDetails[] | undefined => {
|
||||
</tr>
|
||||
<tr>
|
||||
<td>Horizontal FOV</td>
|
||||
<td>{{ videoFormat.horizontalFOV !== undefined ? videoFormat.horizontalFOV.toFixed(2) + "°" : "-" }}</td>
|
||||
<td>
|
||||
{{ videoFormat.horizontalFOV !== undefined ? videoFormat.horizontalFOV.toFixed(2) + "°" : "-" }}
|
||||
</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td>Vertical FOV</td>
|
||||
@@ -242,11 +224,7 @@ const getObservationDetails = (): ObservationDetails[] | undefined => {
|
||||
<td>{{ videoFormat.diagonalFOV !== undefined ? videoFormat.diagonalFOV.toFixed(2) + "°" : "-" }}</td>
|
||||
</tr>
|
||||
<!-- Board warp, only shown for mrcal-calibrated cameras -->
|
||||
<tr
|
||||
v-if="
|
||||
useCameraSettingsStore().getCalibrationCoeffs(props.videoFormat.resolution)?.calobjectWarp?.length === 2
|
||||
"
|
||||
>
|
||||
<tr v-if="currentCalibrationCoeffs?.calobjectWarp?.length === 2">
|
||||
<td>Board warp, X/Y</td>
|
||||
<td>
|
||||
{{
|
||||
@@ -278,7 +256,7 @@ const getObservationDetails = (): ObservationDetails[] | undefined => {
|
||||
<template #expanded-item="{ headers, item }">
|
||||
<td :colspan="headers.length">
|
||||
<div style="display: flex; justify-content: center; width: 100%">
|
||||
<img :src="item.snapshotSrc" alt="observation image" class="snapshot-preview pt-2 pb-2" />
|
||||
<img :src="calibrationImageURL(item.index)" alt="observation image" class="snapshot-preview pt-2 pb-2" />
|
||||
</div>
|
||||
</td>
|
||||
</template>
|
||||
|
||||
@@ -13,11 +13,7 @@ defineProps<{
|
||||
|
||||
const driverMode = computed<boolean>({
|
||||
get: () => useCameraSettingsStore().isDriverMode,
|
||||
set: (v) =>
|
||||
useCameraSettingsStore().changeCurrentPipelineIndex(
|
||||
v ? -1 : useCameraSettingsStore().currentCameraSettings.lastPipelineIndex || 0,
|
||||
true
|
||||
)
|
||||
set: (v) => useCameraSettingsStore().setDriverMode(v)
|
||||
});
|
||||
|
||||
const fpsTooLow = computed<boolean>(() => {
|
||||
|
||||
@@ -130,12 +130,32 @@ const interactiveCols = computed(() =>
|
||||
tooltip="Controls blue automatic white balance gain, which affects how the camera captures colors in different conditions"
|
||||
@input="(args) => useCameraSettingsStore().changeCurrentPipelineSetting({ cameraBlueGain: args }, false)"
|
||||
/>
|
||||
<!-- Disable camera orientation as stop gap for Issue 1084 until calibration data gets rotated. https://github.com/PhotonVision/photonvision/issues/1084 -->
|
||||
<v-banner
|
||||
v-show="
|
||||
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
|
||||
useCameraSettingsStore().currentPipelineSettings.inputImageRotationMode != 0
|
||||
"
|
||||
rounded
|
||||
dark
|
||||
color="red"
|
||||
text-color="white"
|
||||
class="mt-3"
|
||||
icon="mdi-alert-circle-outline"
|
||||
>
|
||||
Warning! A known bug affects rotation of calibrated camera. Turn off rotation here and rotate using
|
||||
cameraToRobotTransform in your robot code.
|
||||
</v-banner>
|
||||
<pv-select
|
||||
v-model="useCameraSettingsStore().currentPipelineSettings.inputImageRotationMode"
|
||||
label="Orientation"
|
||||
tooltip="Rotates the camera stream"
|
||||
tooltip="Rotates the camera stream. Rotation not available when camera has been calibrated."
|
||||
:items="cameraRotations"
|
||||
:select-cols="interactiveCols"
|
||||
:disabled="
|
||||
useCameraSettingsStore().isCurrentVideoFormatCalibrated &&
|
||||
useCameraSettingsStore().currentPipelineSettings.inputImageRotationMode == 0
|
||||
"
|
||||
@input="(args) => useCameraSettingsStore().changeCurrentPipelineSetting({ inputImageRotationMode: args }, false)"
|
||||
/>
|
||||
<pv-select
|
||||
|
||||
@@ -27,42 +27,54 @@ const generalMetrics = computed<MetricItem[]>(() => [
|
||||
value: useSettingsStore().general.gpuAcceleration || "Unknown"
|
||||
}
|
||||
]);
|
||||
const platformMetrics = computed<MetricItem[]>(() => [
|
||||
{
|
||||
header: "CPU Temp",
|
||||
value: useSettingsStore().metrics.cpuTemp === undefined ? "Unknown" : `${useSettingsStore().metrics.cpuTemp}°C`
|
||||
},
|
||||
{
|
||||
header: "CPU Usage",
|
||||
value: useSettingsStore().metrics.cpuUtil === undefined ? "Unknown" : `${useSettingsStore().metrics.cpuUtil}%`
|
||||
},
|
||||
{
|
||||
header: "CPU Memory Usage",
|
||||
value:
|
||||
useSettingsStore().metrics.ramUtil === undefined || useSettingsStore().metrics.cpuMem === undefined
|
||||
? "Unknown"
|
||||
: `${useSettingsStore().metrics.ramUtil || "Unknown"}MB of ${useSettingsStore().metrics.cpuMem}MB`
|
||||
},
|
||||
{
|
||||
header: "GPU Memory Usage",
|
||||
value:
|
||||
useSettingsStore().metrics.gpuMemUtil === undefined || useSettingsStore().metrics.gpuMem === undefined
|
||||
? "Unknown"
|
||||
: `${useSettingsStore().metrics.gpuMemUtil}MB of ${useSettingsStore().metrics.gpuMem}MB`
|
||||
},
|
||||
{
|
||||
header: "CPU Throttling",
|
||||
value: useSettingsStore().metrics.cpuThr || "Unknown"
|
||||
},
|
||||
{
|
||||
header: "CPU Uptime",
|
||||
value: useSettingsStore().metrics.cpuUptime || "Unknown"
|
||||
},
|
||||
{
|
||||
header: "Disk Usage",
|
||||
value: useSettingsStore().metrics.diskUtilPct || "Unknown"
|
||||
|
||||
const platformMetrics = computed<MetricItem[]>(() => {
|
||||
const stats = [
|
||||
{
|
||||
header: "CPU Temp",
|
||||
value: useSettingsStore().metrics.cpuTemp === undefined ? "Unknown" : `${useSettingsStore().metrics.cpuTemp}°C`
|
||||
},
|
||||
{
|
||||
header: "CPU Usage",
|
||||
value: useSettingsStore().metrics.cpuUtil === undefined ? "Unknown" : `${useSettingsStore().metrics.cpuUtil}%`
|
||||
},
|
||||
{
|
||||
header: "CPU Memory Usage",
|
||||
value:
|
||||
useSettingsStore().metrics.ramUtil === undefined || useSettingsStore().metrics.cpuMem === undefined
|
||||
? "Unknown"
|
||||
: `${useSettingsStore().metrics.ramUtil || "Unknown"}MB of ${useSettingsStore().metrics.cpuMem}MB`
|
||||
},
|
||||
{
|
||||
header: "GPU Memory Usage",
|
||||
value:
|
||||
useSettingsStore().metrics.gpuMemUtil === undefined || useSettingsStore().metrics.gpuMem === undefined
|
||||
? "Unknown"
|
||||
: `${useSettingsStore().metrics.gpuMemUtil}MB of ${useSettingsStore().metrics.gpuMem}MB`
|
||||
},
|
||||
{
|
||||
header: "CPU Throttling",
|
||||
value: useSettingsStore().metrics.cpuThr || "Unknown"
|
||||
},
|
||||
{
|
||||
header: "CPU Uptime",
|
||||
value: useSettingsStore().metrics.cpuUptime || "Unknown"
|
||||
},
|
||||
{
|
||||
header: "Disk Usage",
|
||||
value: useSettingsStore().metrics.diskUtilPct || "Unknown"
|
||||
}
|
||||
];
|
||||
|
||||
if (useSettingsStore().metrics.npuUsage) {
|
||||
stats.push({
|
||||
header: "NPU Usage",
|
||||
value: useSettingsStore().metrics.npuUsage || "Unknown"
|
||||
});
|
||||
}
|
||||
]);
|
||||
|
||||
return stats;
|
||||
});
|
||||
|
||||
const metricsLastFetched = ref("Never");
|
||||
const fetchMetrics = () => {
|
||||
|
||||
@@ -59,7 +59,8 @@ const settingsHaveChanged = (): boolean => {
|
||||
a.shouldPublishProto !== b.shouldPublishProto ||
|
||||
a.networkManagerIface !== b.networkManagerIface ||
|
||||
a.setStaticCommand !== b.setStaticCommand ||
|
||||
a.setDHCPcommand !== b.setDHCPcommand
|
||||
a.setDHCPcommand !== b.setDHCPcommand ||
|
||||
a.matchCamerasOnlyByPath !== b.matchCamerasOnlyByPath
|
||||
);
|
||||
};
|
||||
|
||||
@@ -77,6 +78,7 @@ const saveGeneralSettings = () => {
|
||||
setStaticCommand: tempSettingsStruct.value.setStaticCommand || "",
|
||||
shouldManage: tempSettingsStruct.value.shouldManage,
|
||||
shouldPublishProto: tempSettingsStruct.value.shouldPublishProto,
|
||||
matchCamerasOnlyByPath: tempSettingsStruct.value.matchCamerasOnlyByPath,
|
||||
staticIp: tempSettingsStruct.value.staticIp
|
||||
};
|
||||
|
||||
@@ -137,6 +139,8 @@ watchEffect(() => {
|
||||
|
||||
<template>
|
||||
<v-card dark class="mb-3 pr-6 pb-3" style="background-color: #006492">
|
||||
<v-card-title>Global Settings</v-card-title>
|
||||
<v-divider />
|
||||
<v-card-title>Networking</v-card-title>
|
||||
<div class="ml-5">
|
||||
<v-form ref="form" v-model="settingsValid">
|
||||
@@ -254,6 +258,9 @@ watchEffect(() => {
|
||||
>
|
||||
This mode is intended for debugging; it should be off for proper usage. PhotonLib will NOT work!
|
||||
</v-banner>
|
||||
|
||||
<v-divider />
|
||||
<v-card-title>Miscellaneous</v-card-title>
|
||||
<pv-switch
|
||||
v-model="tempSettingsStruct.shouldPublishProto"
|
||||
label="Also Publish Protobuf"
|
||||
@@ -272,6 +279,32 @@ watchEffect(() => {
|
||||
This mode is intended for debugging; it should be off for field use. You may notice a performance hit by using
|
||||
this mode.
|
||||
</v-banner>
|
||||
<pv-switch
|
||||
v-model="tempSettingsStruct.matchCamerasOnlyByPath"
|
||||
label="Strictly match ONLY known cameras"
|
||||
tooltip="ONLY match cameras by the USB port they're plugged into + (basename or USB VID/PID), and never only by the device product string. Also disables automatic detection of new cameras."
|
||||
class="mt-3 mb-2"
|
||||
:label-cols="4"
|
||||
/>
|
||||
<v-banner
|
||||
v-show="tempSettingsStruct.matchCamerasOnlyByPath"
|
||||
rounded
|
||||
color="red"
|
||||
class="mb-3"
|
||||
text-color="white"
|
||||
icon="mdi-information-outline"
|
||||
>
|
||||
Physical cameras will be strictly matched to camera configurations using physical USB port they are plugged
|
||||
into, in addition to device name and other USB metadata. Additionally, no new cameras are allowed to be added.
|
||||
This setting is useful for guaranteeing that an already known and configured camera can never be matched as an
|
||||
"unknown"/"new" camera, which resets pipelines and calibration data.
|
||||
<p />
|
||||
Cameras will NOT be matched if they change USB ports, and new cameras plugged into this coprocessor will NOT
|
||||
be automatically recognized or configured for vision processing.
|
||||
<p />
|
||||
To add a new camera to this coprocessor, disable this setting, connect the camera, and re-enable.
|
||||
</v-banner>
|
||||
<v-divider class="mb-3" />
|
||||
</v-form>
|
||||
<v-btn
|
||||
color="accent"
|
||||
|
||||
@@ -236,6 +236,13 @@ export const useCameraSettingsStore = defineStore("cameraSettings", {
|
||||
}
|
||||
useStateStore().websocket?.send(payload, true);
|
||||
},
|
||||
setDriverMode(isDriverMode: boolean, cameraIndex: number = useStateStore().currentCameraIndex) {
|
||||
const payload = {
|
||||
driverMode: isDriverMode,
|
||||
cameraIndex: cameraIndex
|
||||
};
|
||||
useStateStore().websocket?.send(payload, true);
|
||||
},
|
||||
/**
|
||||
* Change the currently selected pipeline of the provided camera.
|
||||
*
|
||||
@@ -416,6 +423,23 @@ export const useCameraSettingsStore = defineStore("cameraSettings", {
|
||||
cameraIndex: number = useStateStore().currentCameraIndex
|
||||
): CameraCalibrationResult | undefined {
|
||||
return this.cameras[cameraIndex].completeCalibrations.find((v) => resolutionsAreEqual(v.resolution, resolution));
|
||||
},
|
||||
getCalImageUrl(host: string, resolution: Resolution, idx: number, cameraIdx = useStateStore().currentCameraIndex) {
|
||||
const url = new URL(`http://${host}/api/utils/getCalSnapshot`);
|
||||
url.searchParams.set("width", Math.round(resolution.width).toFixed(0));
|
||||
url.searchParams.set("height", Math.round(resolution.height).toFixed(0));
|
||||
url.searchParams.set("snapshotIdx", Math.round(idx).toFixed(0));
|
||||
url.searchParams.set("cameraIdx", Math.round(cameraIdx).toFixed(0));
|
||||
|
||||
return url.href;
|
||||
},
|
||||
getCalJSONUrl(host: string, resolution: Resolution, cameraIdx = useStateStore().currentCameraIndex) {
|
||||
const url = new URL(`http://${host}/api/utils/getCalibrationJSON`);
|
||||
url.searchParams.set("width", Math.round(resolution.width).toFixed(0));
|
||||
url.searchParams.set("height", Math.round(resolution.height).toFixed(0));
|
||||
url.searchParams.set("cameraIdx", Math.round(cameraIdx).toFixed(0));
|
||||
|
||||
return url.href;
|
||||
}
|
||||
}
|
||||
});
|
||||
|
||||
@@ -44,7 +44,9 @@ export const useSettingsStore = defineStore("settings", {
|
||||
connName: "Example Wired Connection",
|
||||
devName: "eth0"
|
||||
}
|
||||
]
|
||||
],
|
||||
networkingDisabled: false,
|
||||
matchCamerasOnlyByPath: false
|
||||
},
|
||||
lighting: {
|
||||
supported: true,
|
||||
@@ -59,7 +61,8 @@ export const useSettingsStore = defineStore("settings", {
|
||||
gpuMemUtil: undefined,
|
||||
cpuThr: undefined,
|
||||
cpuUptime: undefined,
|
||||
diskUtilPct: undefined
|
||||
diskUtilPct: undefined,
|
||||
npuUsage: undefined
|
||||
},
|
||||
currentFieldLayout: {
|
||||
field: {
|
||||
@@ -91,7 +94,8 @@ export const useSettingsStore = defineStore("settings", {
|
||||
gpuMemUtil: data.gpuMemUtil || undefined,
|
||||
cpuThr: data.cpuThr || undefined,
|
||||
cpuUptime: data.cpuUptime || undefined,
|
||||
diskUtilPct: data.diskUtilPct || undefined
|
||||
diskUtilPct: data.diskUtilPct || undefined,
|
||||
npuUsage: data.npuUsage || undefined
|
||||
};
|
||||
},
|
||||
updateGeneralSettingsFromWebsocket(data: WebsocketSettingsUpdate) {
|
||||
|
||||
@@ -20,6 +20,7 @@ export interface MetricData {
|
||||
cpuThr?: string;
|
||||
cpuUptime?: string;
|
||||
diskUtilPct?: string;
|
||||
npuUsage?: string;
|
||||
}
|
||||
|
||||
export enum NetworkConnectionType {
|
||||
@@ -46,6 +47,7 @@ export interface NetworkSettings {
|
||||
setDHCPcommand?: string;
|
||||
networkInterfaceNames: NetworkInterfaceType[];
|
||||
networkingDisabled: boolean;
|
||||
matchCamerasOnlyByPath: boolean;
|
||||
}
|
||||
|
||||
export type ConfigurableNetworkSettings = Omit<
|
||||
@@ -138,6 +140,9 @@ export interface CameraCalibrationResult {
|
||||
distCoeffs: JsonMatOfDouble;
|
||||
observations: BoardObservation[];
|
||||
calobjectWarp?: number[];
|
||||
// We might have to omit observations for bandwith, so backend will send us this
|
||||
numSnapshots: number;
|
||||
meanErrors: number[];
|
||||
}
|
||||
|
||||
export enum ValidQuirks {
|
||||
@@ -255,7 +260,9 @@ export const PlaceholderCameraSettings: CameraSettings = {
|
||||
snapshotName: "img0.png",
|
||||
snapshotData: { rows: 480, cols: 640, type: CvType.CV_8U, data: "" }
|
||||
}
|
||||
]
|
||||
],
|
||||
numSnapshots: 1,
|
||||
meanErrors: [123.45]
|
||||
}
|
||||
],
|
||||
pipelineNicknames: ["Placeholder Pipeline"],
|
||||
|
||||
@@ -37,9 +37,8 @@ dependencies {
|
||||
implementation 'org.zeroturnaround:zt-zip:1.14'
|
||||
|
||||
implementation "org.xerial:sqlite-jdbc:3.41.0.0"
|
||||
def rknnjniversion = "dev-v2024.0.0-44-g8022c40"
|
||||
implementation "org.photonvision:rknn_jni-jni:$rknnjniversion:linuxarm64"
|
||||
implementation "org.photonvision:rknn_jni-java:$rknnjniversion"
|
||||
implementation "org.photonvision:rknn_jni-jni:$rknnVersion:linuxarm64"
|
||||
implementation "org.photonvision:rknn_jni-java:$rknnVersion"
|
||||
implementation "org.photonvision:photon-libcamera-gl-driver-jni:$photonGlDriverLibVersion:linuxarm64"
|
||||
implementation "org.photonvision:photon-libcamera-gl-driver-java:$photonGlDriverLibVersion"
|
||||
|
||||
|
||||
@@ -23,6 +23,7 @@ import com.fasterxml.jackson.annotation.JsonProperty;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.List;
|
||||
import java.util.Optional;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
@@ -51,6 +52,12 @@ public class CameraConfiguration {
|
||||
|
||||
@JsonIgnore public String[] otherPaths = {};
|
||||
|
||||
@JsonProperty("usbVID")
|
||||
public int usbVID = -1;
|
||||
|
||||
@JsonProperty("usbPID")
|
||||
public int usbPID = -1;
|
||||
|
||||
public CameraType cameraType = CameraType.UsbCamera;
|
||||
public double FOV = 70;
|
||||
public final List<CameraCalibrationCoefficients> calibrations;
|
||||
@@ -98,7 +105,9 @@ public class CameraConfiguration {
|
||||
@JsonProperty("cameraType") CameraType cameraType,
|
||||
@JsonProperty("cameraQuirks") QuirkyCamera cameraQuirks,
|
||||
@JsonProperty("calibration") List<CameraCalibrationCoefficients> calibrations,
|
||||
@JsonProperty("currentPipelineIndex") int currentPipelineIndex) {
|
||||
@JsonProperty("currentPipelineIndex") int currentPipelineIndex,
|
||||
@JsonProperty("usbVID") int usbVID,
|
||||
@JsonProperty("usbPID") int usbPID) {
|
||||
this.baseName = baseName;
|
||||
this.uniqueName = uniqueName;
|
||||
this.nickname = nickname;
|
||||
@@ -108,6 +117,8 @@ public class CameraConfiguration {
|
||||
this.cameraQuirks = cameraQuirks;
|
||||
this.calibrations = calibrations != null ? calibrations : new ArrayList<>();
|
||||
this.currentPipelineIndex = currentPipelineIndex;
|
||||
this.usbPID = usbPID;
|
||||
this.usbVID = usbVID;
|
||||
|
||||
logger.debug(
|
||||
"Creating camera configuration for "
|
||||
@@ -156,6 +167,17 @@ public class CameraConfiguration {
|
||||
calibrations.add(calibration);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a unique descriptor of the USB port this camera is attached to. EG
|
||||
* "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1.3:1.0-video-index0"
|
||||
*
|
||||
* @return
|
||||
*/
|
||||
@JsonIgnore
|
||||
public Optional<String> getUSBPath() {
|
||||
return Arrays.stream(otherPaths).filter(path -> path.contains("/by-path/")).findFirst();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "CameraConfiguration [baseName="
|
||||
|
||||
@@ -20,6 +20,24 @@ package org.photonvision.common.configuration;
|
||||
public class HardwareSettings {
|
||||
public int ledBrightnessPercentage = 100;
|
||||
|
||||
@Override
|
||||
public int hashCode() {
|
||||
final int prime = 31;
|
||||
int result = 1;
|
||||
result = prime * result + ledBrightnessPercentage;
|
||||
return result;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object obj) {
|
||||
if (this == obj) return true;
|
||||
if (obj == null) return false;
|
||||
if (getClass() != obj.getClass()) return false;
|
||||
HardwareSettings other = (HardwareSettings) obj;
|
||||
if (ledBrightnessPercentage != other.ledBrightnessPercentage) return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "HardwareSettings [ledBrightnessPercentage=" + ledBrightnessPercentage + "]";
|
||||
|
||||
@@ -39,6 +39,14 @@ public class NetworkConfig {
|
||||
public boolean shouldManage;
|
||||
public boolean shouldPublishProto = false;
|
||||
|
||||
/**
|
||||
* If we should ONLY match cameras by path, and NEVER only by base-name. For now default to false
|
||||
* to preserve old matching logic.
|
||||
*
|
||||
* <p>This also disables creating new CameraConfigurations for detected "new" cameras.
|
||||
*/
|
||||
public boolean matchCamerasOnlyByPath = false;
|
||||
|
||||
@JsonIgnore public static final String NM_IFACE_STRING = "${interface}";
|
||||
@JsonIgnore public static final String NM_IP_STRING = "${ipaddr}";
|
||||
|
||||
@@ -76,7 +84,8 @@ public class NetworkConfig {
|
||||
@JsonProperty("shouldPublishProto") boolean shouldPublishProto,
|
||||
@JsonProperty("networkManagerIface") String networkManagerIface,
|
||||
@JsonProperty("setStaticCommand") String setStaticCommand,
|
||||
@JsonProperty("setDHCPcommand") String setDHCPcommand) {
|
||||
@JsonProperty("setDHCPcommand") String setDHCPcommand,
|
||||
@JsonProperty("matchCamerasOnlyByPath") boolean matchCamerasOnlyByPath) {
|
||||
this.ntServerAddress = ntServerAddress;
|
||||
this.connectionType = connectionType;
|
||||
this.staticIp = staticIp;
|
||||
@@ -86,6 +95,7 @@ public class NetworkConfig {
|
||||
this.networkManagerIface = networkManagerIface;
|
||||
this.setStaticCommand = setStaticCommand;
|
||||
this.setDHCPcommand = setDHCPcommand;
|
||||
this.matchCamerasOnlyByPath = matchCamerasOnlyByPath;
|
||||
setShouldManage(shouldManage);
|
||||
}
|
||||
|
||||
|
||||
@@ -25,12 +25,14 @@ import java.nio.file.Paths;
|
||||
import java.util.List;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.rknn.RknnJNI;
|
||||
|
||||
public class NeuralNetworkModelManager {
|
||||
private static NeuralNetworkModelManager INSTANCE;
|
||||
private static final Logger logger = new Logger(NeuralNetworkModelManager.class, LogGroup.Config);
|
||||
|
||||
private final String MODEL_NAME = "note-640-640-yolov5s.rknn";
|
||||
private final RknnJNI.ModelVersion modelVersion = RknnJNI.ModelVersion.YOLO_V5;
|
||||
private File defaultModelFile;
|
||||
private List<String> labels;
|
||||
|
||||
@@ -51,7 +53,7 @@ public class NeuralNetworkModelManager {
|
||||
this.defaultModelFile = new File(modelsFolder, MODEL_NAME);
|
||||
extractResource(modelResourcePath, defaultModelFile);
|
||||
|
||||
File labelsFile = new File(modelsFolder, "labels.txt");
|
||||
File labelsFile = new File(modelsFolder, "labels_v5.txt");
|
||||
var labelResourcePath = "/models/" + labelsFile.getName();
|
||||
extractResource(labelResourcePath, labelsFile);
|
||||
|
||||
@@ -95,4 +97,8 @@ public class NeuralNetworkModelManager {
|
||||
public List<String> getLabels() {
|
||||
return labels;
|
||||
}
|
||||
|
||||
public RknnJNI.ModelVersion getModelVersion() {
|
||||
return modelVersion;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -31,7 +31,7 @@ import org.photonvision.common.util.SerializationUtils;
|
||||
import org.photonvision.jni.RknnDetectorJNI;
|
||||
import org.photonvision.mrcal.MrCalJNILoader;
|
||||
import org.photonvision.raspi.LibCameraJNILoader;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.calibration.UICameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.camera.QuirkyCamera;
|
||||
import org.photonvision.vision.processes.VisionModule;
|
||||
import org.photonvision.vision.processes.VisionModuleManager;
|
||||
@@ -126,13 +126,6 @@ public class PhotonConfiguration {
|
||||
|
||||
settingsSubmap.put("networkSettings", netConfigMap);
|
||||
|
||||
map.put(
|
||||
"cameraSettings",
|
||||
VisionModuleManager.getInstance().getModules().stream()
|
||||
.map(VisionModule::toUICameraConfig)
|
||||
.map(SerializationUtils::objectToHashMap)
|
||||
.collect(Collectors.toList()));
|
||||
|
||||
var lightingConfig = new UILightingConfig();
|
||||
lightingConfig.brightness = hardwareSettings.ledBrightnessPercentage;
|
||||
lightingConfig.supported = !hardwareConfig.ledPins.isEmpty();
|
||||
@@ -181,7 +174,7 @@ public class PhotonConfiguration {
|
||||
public HashMap<Integer, HashMap<String, Object>> videoFormatList;
|
||||
public int outputStreamPort;
|
||||
public int inputStreamPort;
|
||||
public List<CameraCalibrationCoefficients> calibrations;
|
||||
public List<UICameraCalibrationCoefficients> calibrations;
|
||||
public boolean isFovConfigurable = true;
|
||||
public QuirkyCamera cameraQuirks;
|
||||
public boolean isCSICamera;
|
||||
|
||||
@@ -26,6 +26,7 @@ import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.SerializationUtils;
|
||||
import org.photonvision.vision.pipeline.result.CVPipelineResult;
|
||||
import org.photonvision.vision.pipeline.result.CalibrationPipelineResult;
|
||||
|
||||
public class UIDataPublisher implements CVPipelineResultConsumer {
|
||||
private static final Logger logger = new Logger(UIDataPublisher.class, LogGroup.VisionModule);
|
||||
@@ -41,16 +42,22 @@ public class UIDataPublisher implements CVPipelineResultConsumer {
|
||||
public void accept(CVPipelineResult result) {
|
||||
long now = System.currentTimeMillis();
|
||||
|
||||
// only update the UI at 15hz
|
||||
// only update the UI at 10hz
|
||||
if (lastUIResultUpdateTime + 1000.0 / 10.0 > now) return;
|
||||
|
||||
var dataMap = new HashMap<String, Object>();
|
||||
dataMap.put("fps", result.fps);
|
||||
dataMap.put("latency", result.getLatencyMillis());
|
||||
var uiTargets = new ArrayList<HashMap<String, Object>>(result.targets.size());
|
||||
for (var t : result.targets) {
|
||||
uiTargets.add(t.toHashMap());
|
||||
|
||||
// We don't actually need to send targets during calibration and it can take up a lot (up to
|
||||
// 1.2Mbps for 60 snapshots) of target results with no pitch/yaw/etc set
|
||||
if (!(result instanceof CalibrationPipelineResult)) {
|
||||
for (var t : result.targets) {
|
||||
uiTargets.add(t.toHashMap());
|
||||
}
|
||||
}
|
||||
|
||||
dataMap.put("targets", uiTargets);
|
||||
dataMap.put("classNames", result.objectDetectionClassNames);
|
||||
|
||||
|
||||
@@ -92,6 +92,10 @@ public class MetricsManager {
|
||||
return safeExecute(cmds.cpuThrottleReasonCmd);
|
||||
}
|
||||
|
||||
public String getNpuUsage() {
|
||||
return safeExecute(cmds.npuUsageCommand);
|
||||
}
|
||||
|
||||
private String gpuMemSave = null;
|
||||
|
||||
public String getGPUMemorySplit() {
|
||||
@@ -128,6 +132,7 @@ public class MetricsManager {
|
||||
metrics.put("ramUtil", this.getUsedRam());
|
||||
metrics.put("gpuMemUtil", this.getMallocedMemory());
|
||||
metrics.put("diskUtilPct", this.getUsedDiskPct());
|
||||
metrics.put("npuUsage", this.getNpuUsage());
|
||||
|
||||
DataChangeService.getInstance().publishEvent(OutgoingUIEvent.wrappedOf("metrics", metrics));
|
||||
}
|
||||
|
||||
@@ -29,6 +29,8 @@ public class CmdBase {
|
||||
// GPU
|
||||
public String gpuMemoryCommand = "";
|
||||
public String gpuMemUsageCommand = "";
|
||||
// NPU
|
||||
public String npuUsageCommand = "";
|
||||
// RAM
|
||||
public String ramUsageCommand = "";
|
||||
// Disk
|
||||
|
||||
@@ -44,5 +44,7 @@ public class RK3588Cmds extends LinuxCmds {
|
||||
*/
|
||||
cpuTemperatureCommand =
|
||||
"cat /sys/class/thermal/thermal_zone1/temp | awk '{printf \"%.1f\", $1/1000}'";
|
||||
|
||||
npuUsageCommand = "cat /sys/kernel/debug/rknpu/load | sed 's/NPU load://; s/^ *//; s/ *$//'";
|
||||
}
|
||||
}
|
||||
|
||||
@@ -23,5 +23,6 @@ public enum LogGroup {
|
||||
VisionModule,
|
||||
Data,
|
||||
General,
|
||||
Config
|
||||
Config,
|
||||
CSCore,
|
||||
}
|
||||
|
||||
@@ -99,6 +99,7 @@ public class Logger {
|
||||
levelMap.put(LogGroup.Data, LogLevel.INFO);
|
||||
levelMap.put(LogGroup.VisionModule, LogLevel.INFO);
|
||||
levelMap.put(LogGroup.Config, LogLevel.INFO);
|
||||
levelMap.put(LogGroup.CSCore, LogLevel.TRACE);
|
||||
}
|
||||
|
||||
static {
|
||||
@@ -194,7 +195,7 @@ public class Logger {
|
||||
return logLevel.code <= levelMap.get(group).code;
|
||||
}
|
||||
|
||||
private void log(String message, LogLevel level) {
|
||||
void log(String message, LogLevel level) {
|
||||
if (shouldLog(level)) {
|
||||
log(message, level, group, className);
|
||||
}
|
||||
|
||||
@@ -0,0 +1,70 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.common.logging;
|
||||
|
||||
import edu.wpi.first.cscore.CameraServerJNI;
|
||||
import java.nio.file.Path;
|
||||
|
||||
/** Redirect cscore logs to our logger */
|
||||
public class PvCSCoreLogger {
|
||||
private static PvCSCoreLogger INSTANCE;
|
||||
|
||||
public static PvCSCoreLogger getInstance() {
|
||||
if (INSTANCE == null) {
|
||||
INSTANCE = new PvCSCoreLogger();
|
||||
}
|
||||
return INSTANCE;
|
||||
}
|
||||
|
||||
private Logger logger;
|
||||
|
||||
private PvCSCoreLogger() {
|
||||
CameraServerJNI.setLogger(this::logMsg, 7);
|
||||
this.logger = new Logger(getClass(), LogGroup.CSCore);
|
||||
}
|
||||
|
||||
private void logMsg(int level, String file, int line, String msg) {
|
||||
if (level == 20) {
|
||||
logger.info(msg);
|
||||
return;
|
||||
}
|
||||
|
||||
file = Path.of(file).getFileName().toString();
|
||||
|
||||
String levelmsg;
|
||||
LogLevel pvlevel;
|
||||
if (level >= 50) {
|
||||
levelmsg = "CRITICAL";
|
||||
pvlevel = LogLevel.ERROR;
|
||||
} else if (level >= 40) {
|
||||
levelmsg = "ERROR";
|
||||
pvlevel = LogLevel.ERROR;
|
||||
} else if (level >= 30) {
|
||||
levelmsg = "WARNING";
|
||||
pvlevel = LogLevel.WARN;
|
||||
} else if (level >= 20) {
|
||||
levelmsg = "INFO";
|
||||
pvlevel = LogLevel.INFO;
|
||||
} else {
|
||||
levelmsg = "DEBUG";
|
||||
pvlevel = LogLevel.DEBUG;
|
||||
}
|
||||
logger.log(
|
||||
"CS: " + levelmsg + " " + level + ": " + msg + " (" + file + ":" + line + ")", pvlevel);
|
||||
}
|
||||
}
|
||||
@@ -22,12 +22,12 @@ import java.util.Arrays;
|
||||
import java.util.List;
|
||||
import java.util.concurrent.CopyOnWriteArrayList;
|
||||
import java.util.stream.Collectors;
|
||||
import org.opencv.core.Mat;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.util.TestUtils;
|
||||
import org.photonvision.rknn.RknnJNI;
|
||||
import org.photonvision.rknn.RknnJNI.RknnResult;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.pipe.impl.NeuralNetworkPipeResult;
|
||||
|
||||
public class RknnDetectorJNI extends PhotonJNICommon {
|
||||
@@ -65,17 +65,38 @@ public class RknnDetectorJNI extends PhotonJNICommon {
|
||||
long objPointer = -1;
|
||||
private List<String> labels;
|
||||
private final Object lock = new Object();
|
||||
private static final CopyOnWriteArrayList<RknnObjectDetector> detectors =
|
||||
new CopyOnWriteArrayList<>();
|
||||
|
||||
private static final CopyOnWriteArrayList<Long> detectors = new CopyOnWriteArrayList<>();
|
||||
static volatile boolean hook = false;
|
||||
|
||||
public RknnObjectDetector(String modelPath, List<String> labels) {
|
||||
public RknnObjectDetector(String modelPath, List<String> labels, RknnJNI.ModelVersion version) {
|
||||
synchronized (lock) {
|
||||
objPointer = RknnJNI.create(modelPath, labels.size());
|
||||
detectors.add(objPointer);
|
||||
System.out.println(
|
||||
"Created " + objPointer + "! Detectors: " + Arrays.toString(detectors.toArray()));
|
||||
objPointer = RknnJNI.create(modelPath, labels.size(), version.ordinal(), -1);
|
||||
detectors.add(this);
|
||||
logger.debug(
|
||||
"Created detector "
|
||||
+ objPointer
|
||||
+ " from path "
|
||||
+ modelPath
|
||||
+ "! Detectors: "
|
||||
+ Arrays.toString(detectors.toArray()));
|
||||
}
|
||||
this.labels = labels;
|
||||
|
||||
// the kernel should probably alredy deal with this for us, but I'm gunna be paranoid anyways.
|
||||
if (!hook) {
|
||||
Runtime.getRuntime()
|
||||
.addShutdownHook(
|
||||
new Thread(
|
||||
() -> {
|
||||
System.err.println("Shutdown hook rknn");
|
||||
for (var d : detectors) {
|
||||
d.release();
|
||||
}
|
||||
}));
|
||||
hook = true;
|
||||
}
|
||||
}
|
||||
|
||||
public List<String> getClasses() {
|
||||
@@ -90,14 +111,14 @@ public class RknnDetectorJNI extends PhotonJNICommon {
|
||||
* @param boxThresh Minimum confidence for a box to be added. Basically just confidence
|
||||
* threshold
|
||||
*/
|
||||
public List<NeuralNetworkPipeResult> detect(CVMat in, double nmsThresh, double boxThresh) {
|
||||
public List<NeuralNetworkPipeResult> detect(Mat in, double nmsThresh, double boxThresh) {
|
||||
RknnResult[] ret;
|
||||
synchronized (lock) {
|
||||
// We can technically be asked to detect and the lock might be acquired _after_ release has
|
||||
// been called. This would mean objPointer would be invalid which would call everything to
|
||||
// explode.
|
||||
if (objPointer > 0) {
|
||||
ret = RknnJNI.detect(objPointer, in.getMat().getNativeObjAddr(), nmsThresh, boxThresh);
|
||||
ret = RknnJNI.detect(objPointer, in.getNativeObjAddr(), nmsThresh, boxThresh);
|
||||
} else {
|
||||
logger.warn("Detect called after destroy -- giving up");
|
||||
return List.of();
|
||||
@@ -115,7 +136,7 @@ public class RknnDetectorJNI extends PhotonJNICommon {
|
||||
synchronized (lock) {
|
||||
if (objPointer > 0) {
|
||||
RknnJNI.destroy(objPointer);
|
||||
detectors.remove(objPointer);
|
||||
detectors.remove(this);
|
||||
System.out.println(
|
||||
"Killed " + objPointer + "! Detectors: " + Arrays.toString(detectors.toArray()));
|
||||
objPointer = -1;
|
||||
@@ -125,14 +146,4 @@ public class RknnDetectorJNI extends PhotonJNICommon {
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// public static void createRknnDetector() {
|
||||
// objPointer =
|
||||
// RknnJNI.create(
|
||||
// NeuralNetworkModelManager.getInstance()
|
||||
// .getDefaultRknnModel()
|
||||
// .getAbsolutePath()
|
||||
// .toString(),
|
||||
// NeuralNetworkModelManager.getInstance().getLabels().size());
|
||||
// }
|
||||
}
|
||||
|
||||
@@ -53,6 +53,7 @@ public class MrCalJNILoader extends PhotonJNICommon {
|
||||
"libcolamd",
|
||||
"libccolamd",
|
||||
"openblas",
|
||||
"libwinpthread-1",
|
||||
"libgcc_s_seh-1",
|
||||
"libquadmath-0",
|
||||
"libgfortran-5",
|
||||
|
||||
@@ -23,16 +23,37 @@ import java.util.Comparator;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.objdetect.ArucoDetector;
|
||||
import org.opencv.objdetect.DetectorParameters;
|
||||
import org.opencv.objdetect.Dictionary;
|
||||
import org.opencv.objdetect.Objdetect;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
|
||||
/** This class wraps an {@link ArucoDetector} for convenience. */
|
||||
public class PhotonArucoDetector {
|
||||
public class PhotonArucoDetector implements Releasable {
|
||||
private static final Logger logger = new Logger(PhotonArucoDetector.class, LogGroup.VisionModule);
|
||||
|
||||
private final ArucoDetector detector =
|
||||
new ArucoDetector(Objdetect.getPredefinedDictionary(Objdetect.DICT_APRILTAG_16h5));
|
||||
private static class ArucoDetectorHack extends ArucoDetector {
|
||||
public ArucoDetectorHack(Dictionary predefinedDictionary) {
|
||||
super(predefinedDictionary);
|
||||
}
|
||||
|
||||
// avoid double-free by keeping track of this ourselves (ew)
|
||||
private boolean freed = false;
|
||||
|
||||
@Override
|
||||
public void finalize() throws Throwable {
|
||||
if (freed) {
|
||||
return;
|
||||
}
|
||||
|
||||
super.finalize();
|
||||
freed = true;
|
||||
}
|
||||
}
|
||||
|
||||
private final ArucoDetectorHack detector =
|
||||
new ArucoDetectorHack(Objdetect.getPredefinedDictionary(Objdetect.DICT_APRILTAG_16h5));
|
||||
|
||||
private final Mat ids = new Mat();
|
||||
private final ArrayList<Mat> cornerMats = new ArrayList<>();
|
||||
@@ -95,4 +116,16 @@ public class PhotonArucoDetector {
|
||||
|
||||
return results;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
try {
|
||||
detector.finalize();
|
||||
} catch (Throwable e) {
|
||||
logger.error("Exception destroying PhotonArucoDetector", e);
|
||||
}
|
||||
ids.release();
|
||||
for (var m : cornerMats) m.release();
|
||||
cornerMats.clear();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -24,7 +24,7 @@ import java.util.List;
|
||||
import org.opencv.core.Point;
|
||||
import org.opencv.core.Point3;
|
||||
|
||||
public final class BoardObservation {
|
||||
public final class BoardObservation implements Cloneable {
|
||||
// Expected feature 3d location in the camera frame
|
||||
@JsonProperty("locationInObjectSpace")
|
||||
public List<Point3> locationInObjectSpace;
|
||||
@@ -68,4 +68,33 @@ public final class BoardObservation {
|
||||
this.snapshotName = snapshotName;
|
||||
this.snapshotData = snapshotData;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "BoardObservation [locationInObjectSpace="
|
||||
+ locationInObjectSpace
|
||||
+ ", locationInImageSpace="
|
||||
+ locationInImageSpace
|
||||
+ ", reprojectionErrors="
|
||||
+ reprojectionErrors
|
||||
+ ", optimisedCameraToObject="
|
||||
+ optimisedCameraToObject
|
||||
+ ", includeObservationInCalibration="
|
||||
+ includeObservationInCalibration
|
||||
+ ", snapshotName="
|
||||
+ snapshotName
|
||||
+ ", snapshotData="
|
||||
+ snapshotData
|
||||
+ "]";
|
||||
}
|
||||
|
||||
@Override
|
||||
public BoardObservation clone() {
|
||||
try {
|
||||
return (BoardObservation) super.clone();
|
||||
} catch (CloneNotSupportedException e) {
|
||||
System.err.println("Guhhh clone buh");
|
||||
return null;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -191,8 +191,8 @@ public class CameraCalibrationCoefficients implements Releasable {
|
||||
+ cameraIntrinsics
|
||||
+ ", distCoeffs="
|
||||
+ distCoeffs
|
||||
+ ", observations="
|
||||
+ observations
|
||||
+ ", observationslen="
|
||||
+ observations.size()
|
||||
+ ", calobjectWarp="
|
||||
+ Arrays.toString(calobjectWarp)
|
||||
+ ", intrinsicsArr="
|
||||
@@ -201,4 +201,16 @@ public class CameraCalibrationCoefficients implements Releasable {
|
||||
+ Arrays.toString(distCoeffsArr)
|
||||
+ "]";
|
||||
}
|
||||
|
||||
public UICameraCalibrationCoefficients cloneWithoutObservations() {
|
||||
return new UICameraCalibrationCoefficients(
|
||||
resolution,
|
||||
cameraIntrinsics,
|
||||
distCoeffs,
|
||||
calobjectWarp,
|
||||
observations,
|
||||
calobjectSize,
|
||||
calobjectSpacing,
|
||||
lensmodel);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -76,4 +76,17 @@ public class JsonImageMat implements Releasable {
|
||||
public void release() {
|
||||
if (wrappedMat != null) wrappedMat.release();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "JsonImageMat [rows="
|
||||
+ rows
|
||||
+ ", cols="
|
||||
+ cols
|
||||
+ ", type="
|
||||
+ type
|
||||
+ ", datalen="
|
||||
+ data.length()
|
||||
+ "]";
|
||||
}
|
||||
}
|
||||
|
||||
@@ -40,7 +40,7 @@ public class JsonMatOfDouble implements Releasable {
|
||||
@JsonIgnore private Mat wrappedMat = null;
|
||||
@JsonIgnore private Matrix wpilibMat = null;
|
||||
|
||||
private MatOfDouble wrappedMatOfDouble;
|
||||
@JsonIgnore private MatOfDouble wrappedMatOfDouble;
|
||||
|
||||
public JsonMatOfDouble(int rows, int cols, double[] data) {
|
||||
this(rows, cols, CvType.CV_64FC1, data);
|
||||
|
||||
@@ -0,0 +1,59 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.calibration;
|
||||
|
||||
import java.util.List;
|
||||
import java.util.stream.Collectors;
|
||||
import org.opencv.core.Size;
|
||||
|
||||
public class UICameraCalibrationCoefficients extends CameraCalibrationCoefficients {
|
||||
public int numSnapshots;
|
||||
public List<Double> meanErrors;
|
||||
|
||||
public UICameraCalibrationCoefficients(
|
||||
Size resolution,
|
||||
JsonMatOfDouble cameraIntrinsics,
|
||||
JsonMatOfDouble distCoeffs,
|
||||
double[] calobjectWarp,
|
||||
List<BoardObservation> observations,
|
||||
Size calobjectSize,
|
||||
double calobjectSpacing,
|
||||
CameraLensModel lensmodel) {
|
||||
// yeet observations, keep all else
|
||||
super(
|
||||
resolution,
|
||||
cameraIntrinsics,
|
||||
distCoeffs,
|
||||
calobjectWarp,
|
||||
List.of(),
|
||||
calobjectSize,
|
||||
calobjectSpacing,
|
||||
lensmodel);
|
||||
|
||||
this.numSnapshots = observations.size();
|
||||
this.meanErrors =
|
||||
observations.stream()
|
||||
.map(
|
||||
it2 ->
|
||||
it2.reprojectionErrors.stream()
|
||||
.mapToDouble(it -> Math.sqrt(it.x * it.x + it.y * it.y))
|
||||
.average()
|
||||
.orElse(0))
|
||||
.collect(Collectors.toList());
|
||||
}
|
||||
}
|
||||
@@ -19,6 +19,8 @@ package org.photonvision.vision.camera;
|
||||
|
||||
import edu.wpi.first.cscore.UsbCameraInfo;
|
||||
import java.util.Arrays;
|
||||
import java.util.Optional;
|
||||
import org.photonvision.common.hardware.Platform;
|
||||
|
||||
public class CameraInfo extends UsbCameraInfo {
|
||||
public final CameraType cameraType;
|
||||
@@ -68,15 +70,54 @@ public class CameraInfo extends UsbCameraInfo {
|
||||
return getBaseName().replaceAll(" ", "_");
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a unique descriptor of the USB port this camera is attached to. EG
|
||||
* "/dev/v4l/by-path/platform-fc800000.usb-usb-0:1.3:1.0-video-index0"
|
||||
*
|
||||
* @return
|
||||
*/
|
||||
public Optional<String> getUSBPath() {
|
||||
return Arrays.stream(otherPaths).filter(path -> path.contains("/by-path/")).findFirst();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean equals(Object o) {
|
||||
if (o == this) return true;
|
||||
if (!(o instanceof UsbCameraInfo || o instanceof CameraInfo)) return false;
|
||||
UsbCameraInfo other = (UsbCameraInfo) o;
|
||||
return path.equals(other.path)
|
||||
// && a.dev == b.dev (dev is not constant in Windows)
|
||||
&& name.equals(other.name)
|
||||
&& productId == other.productId
|
||||
&& vendorId == other.vendorId;
|
||||
public boolean equals(Object obj) {
|
||||
if (this == obj) return true;
|
||||
if (obj == null) return false;
|
||||
if (getClass() != obj.getClass()) return false;
|
||||
CameraInfo other = (CameraInfo) obj;
|
||||
|
||||
// Windows device number is not significant. See
|
||||
// https://github.com/wpilibsuite/allwpilib/blob/4b94a64b06057c723d6fcafeb1a45f55a70d179a/cscore/src/main/native/windows/UsbCameraImpl.cpp#L1128
|
||||
if (!Platform.isWindows()) {
|
||||
if (dev != other.dev) return false;
|
||||
}
|
||||
|
||||
if (!path.equals(other.path)) return false;
|
||||
if (!name.equals(other.name)) return false;
|
||||
if (!Arrays.asList(this.otherPaths).containsAll(Arrays.asList(other.otherPaths))) return false;
|
||||
if (vendorId != other.vendorId) return false;
|
||||
if (productId != other.productId) return false;
|
||||
|
||||
// Don't trust super.equals, as it compares references. Should PR this to allwpilib at some
|
||||
// point
|
||||
return true;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "CameraInfo [cameraType="
|
||||
+ cameraType
|
||||
+ ", baseName="
|
||||
+ getBaseName()
|
||||
+ ", vid="
|
||||
+ vendorId
|
||||
+ ", pid="
|
||||
+ productId
|
||||
+ ", path="
|
||||
+ path
|
||||
+ ", otherPaths="
|
||||
+ Arrays.toString(otherPaths)
|
||||
+ "]";
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,93 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.camera;
|
||||
|
||||
import java.util.*;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.vision.frame.Frame;
|
||||
import org.photonvision.vision.frame.FrameProvider;
|
||||
import org.photonvision.vision.frame.FrameThresholdType;
|
||||
import org.photonvision.vision.opencv.ImageRotationMode;
|
||||
import org.photonvision.vision.pipe.impl.HSVPipe.HSVParams;
|
||||
import org.photonvision.vision.processes.VisionSource;
|
||||
import org.photonvision.vision.processes.VisionSourceSettables;
|
||||
|
||||
/** Dummy class for unit testing the vision source manager */
|
||||
public class TestSource extends VisionSource {
|
||||
private FrameProvider usbFrameProvider;
|
||||
|
||||
public TestSource(CameraConfiguration config) {
|
||||
super(config);
|
||||
|
||||
if (getCameraConfiguration().cameraQuirks == null)
|
||||
getCameraConfiguration().cameraQuirks =
|
||||
QuirkyCamera.getQuirkyCamera(config.usbVID, config.usbVID, config.baseName);
|
||||
}
|
||||
|
||||
@Override
|
||||
public FrameProvider getFrameProvider() {
|
||||
return new FrameProvider() {
|
||||
@Override
|
||||
public Frame get() {
|
||||
// TODO Auto-generated method stub
|
||||
throw new UnsupportedOperationException("Unimplemented method 'get'");
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getName() {
|
||||
return cameraConfiguration.uniqueName;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void requestFrameThresholdType(FrameThresholdType type) {
|
||||
// TODO Auto-generated method stub
|
||||
throw new UnsupportedOperationException("Unimplemented method 'requestFrameThresholdType'");
|
||||
}
|
||||
|
||||
@Override
|
||||
public void requestFrameRotation(ImageRotationMode rotationMode) {
|
||||
// TODO Auto-generated method stub
|
||||
throw new UnsupportedOperationException("Unimplemented method 'requestFrameRotation'");
|
||||
}
|
||||
|
||||
@Override
|
||||
public void requestFrameCopies(boolean copyInput, boolean copyOutput) {
|
||||
// TODO Auto-generated method stub
|
||||
throw new UnsupportedOperationException("Unimplemented method 'requestFrameCopies'");
|
||||
}
|
||||
|
||||
@Override
|
||||
public void requestHsvSettings(HSVParams params) {
|
||||
// TODO Auto-generated method stub
|
||||
throw new UnsupportedOperationException("Unimplemented method 'requestHsvSettings'");
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
@Override
|
||||
public VisionSourceSettables getSettables() {
|
||||
// TODO Auto-generated method stub
|
||||
throw new UnsupportedOperationException("Unimplemented method 'getSettables'");
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isVendorCamera() {
|
||||
// TODO Auto-generated method stub
|
||||
throw new UnsupportedOperationException("Unimplemented method 'isVendorCamera'");
|
||||
}
|
||||
}
|
||||
@@ -49,9 +49,17 @@ public class USBCameraSource extends VisionSource {
|
||||
super(config);
|
||||
|
||||
logger = new Logger(USBCameraSource.class, config.nickname, LogGroup.Camera);
|
||||
camera = new UsbCamera(config.nickname, config.path);
|
||||
// cscore will auto-reconnect to the camera path we give it. v4l does not guarantee that if i
|
||||
// swap cameras around, the same /dev/videoN ID will be assigned to that camera. So instead
|
||||
// default to pinning to a particular USB port, or by "path" (appears to be a global identifier)
|
||||
// on Windows.
|
||||
camera = new UsbCamera(config.nickname, config.getUSBPath().orElse(config.path));
|
||||
cvSink = CameraServer.getVideo(this.camera);
|
||||
|
||||
// set vid/pid if not done already for future matching
|
||||
if (config.usbVID <= 0) config.usbVID = this.camera.getInfo().vendorId;
|
||||
if (config.usbPID <= 0) config.usbPID = this.camera.getInfo().productId;
|
||||
|
||||
if (getCameraConfiguration().cameraQuirks == null)
|
||||
getCameraConfiguration().cameraQuirks =
|
||||
QuirkyCamera.getQuirkyCamera(
|
||||
@@ -262,9 +270,13 @@ public class USBCameraSource extends VisionSource {
|
||||
if (getCameraConfiguration().cameraQuirks.hasQuirk(CameraQuirk.ArduOV9281)) {
|
||||
propMin = 1;
|
||||
propMax = 75;
|
||||
} else if (getCameraConfiguration().cameraQuirks.hasQuirk(CameraQuirk.ArduOV2311)) {
|
||||
propMin = 1;
|
||||
propMax = 140;
|
||||
}
|
||||
|
||||
var exposure_manual_val = MathUtils.map(Math.round(exposure), 0, 100, propMin, propMax);
|
||||
logger.debug("Setting camera exposure to " + exposure_manual_val);
|
||||
prop.set((int) exposure_manual_val);
|
||||
} else {
|
||||
scaledExposure = (int) Math.round(exposure);
|
||||
@@ -395,6 +407,7 @@ public class USBCameraSource extends VisionSource {
|
||||
// Sort by resolution
|
||||
var sortedList =
|
||||
videoModesList.stream()
|
||||
.distinct() // remove redundant video mode entries
|
||||
.sorted(((a, b) -> (b.width + b.height) - (a.width + a.height)))
|
||||
.collect(Collectors.toList());
|
||||
Collections.reverse(sortedList);
|
||||
|
||||
@@ -33,7 +33,7 @@ import org.photonvision.vision.opencv.CVMat;
|
||||
* path}.
|
||||
*/
|
||||
public class FileFrameProvider extends CpuImageProcessor {
|
||||
public static final int MAX_FPS = 5;
|
||||
public static final int MAX_FPS = 10;
|
||||
private static int count = 0;
|
||||
|
||||
private final int thisIndex = count++;
|
||||
|
||||
@@ -21,11 +21,13 @@ import edu.wpi.first.apriltag.AprilTagDetection;
|
||||
import edu.wpi.first.apriltag.AprilTagDetector;
|
||||
import java.util.List;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class AprilTagDetectionPipe
|
||||
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionPipeParams> {
|
||||
private final AprilTagDetector m_detector = new AprilTagDetector();
|
||||
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionPipeParams>
|
||||
implements Releasable {
|
||||
private AprilTagDetector m_detector = new AprilTagDetector();
|
||||
|
||||
public AprilTagDetectionPipe() {
|
||||
super();
|
||||
@@ -40,6 +42,10 @@ public class AprilTagDetectionPipe
|
||||
return List.of();
|
||||
}
|
||||
|
||||
if (m_detector == null) {
|
||||
throw new RuntimeException("Apriltag detector was released!");
|
||||
}
|
||||
|
||||
var ret = m_detector.detect(in.getMat());
|
||||
|
||||
if (ret == null) {
|
||||
@@ -60,4 +66,10 @@ public class AprilTagDetectionPipe
|
||||
|
||||
super.setParams(newParams);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
m_detector.close();
|
||||
m_detector = null;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -25,13 +25,15 @@ import org.opencv.calib3d.Calib3d;
|
||||
import org.opencv.core.MatOfPoint2f;
|
||||
import org.opencv.core.Point;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class AprilTagPoseEstimatorPipe
|
||||
extends CVPipe<
|
||||
AprilTagDetection,
|
||||
AprilTagPoseEstimate,
|
||||
AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams> {
|
||||
AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams>
|
||||
implements Releasable {
|
||||
private final AprilTagPoseEstimator m_poseEstimator =
|
||||
new AprilTagPoseEstimator(new AprilTagPoseEstimator.Config(0, 0, 0, 0, 0));
|
||||
|
||||
@@ -92,6 +94,11 @@ public class AprilTagPoseEstimatorPipe
|
||||
super.setParams(newParams);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
temp.release();
|
||||
}
|
||||
|
||||
public static class AprilTagPoseEstimatorPipeParams {
|
||||
final AprilTagPoseEstimator.Config config;
|
||||
final CameraCalibrationCoefficients calibration;
|
||||
|
||||
@@ -29,10 +29,12 @@ import org.opencv.objdetect.Objdetect;
|
||||
import org.photonvision.vision.aruco.ArucoDetectionResult;
|
||||
import org.photonvision.vision.aruco.PhotonArucoDetector;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class ArucoDetectionPipe
|
||||
extends CVPipe<CVMat, List<ArucoDetectionResult>, ArucoDetectionPipeParams> {
|
||||
extends CVPipe<CVMat, List<ArucoDetectionResult>, ArucoDetectionPipeParams>
|
||||
implements Releasable {
|
||||
// ArucoDetector wrapper class
|
||||
private final PhotonArucoDetector photonDetector = new PhotonArucoDetector();
|
||||
|
||||
@@ -131,4 +133,9 @@ public class ArucoDetectionPipe
|
||||
var pt2 = new Point(corner.x + windowSize, corner.y + windowSize);
|
||||
Imgproc.rectangle(outputMat, pt1, pt2, new Scalar(0, 0, 255), thickness);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
photonDetector.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -32,13 +32,15 @@ import org.opencv.core.MatOfPoint3f;
|
||||
import org.opencv.core.Point3;
|
||||
import org.photonvision.vision.aruco.ArucoDetectionResult;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class ArucoPoseEstimatorPipe
|
||||
extends CVPipe<
|
||||
ArucoDetectionResult,
|
||||
AprilTagPoseEstimate,
|
||||
ArucoPoseEstimatorPipe.ArucoPoseEstimatorPipeParams> {
|
||||
ArucoPoseEstimatorPipe.ArucoPoseEstimatorPipeParams>
|
||||
implements Releasable {
|
||||
// image points of marker corners
|
||||
private final MatOfPoint2f imagePoints = new MatOfPoint2f(Mat.zeros(4, 1, CvType.CV_32FC2));
|
||||
// rvec/tvec estimations from solvepnp
|
||||
@@ -117,6 +119,18 @@ public class ArucoPoseEstimatorPipe
|
||||
super.setParams(newParams);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
imagePoints.release();
|
||||
for (var m : rvecs) m.release();
|
||||
rvecs.clear();
|
||||
for (var m : tvecs) m.release();
|
||||
tvecs.clear();
|
||||
rvec.release();
|
||||
tvec.release();
|
||||
reprojectionErrors.release();
|
||||
}
|
||||
|
||||
public static class ArucoPoseEstimatorPipeParams {
|
||||
final CameraCalibrationCoefficients calibration;
|
||||
final double tagSize;
|
||||
|
||||
@@ -38,13 +38,26 @@ import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.calibration.CameraLensModel;
|
||||
import org.photonvision.vision.calibration.JsonImageMat;
|
||||
import org.photonvision.vision.calibration.JsonMatOfDouble;
|
||||
import org.photonvision.vision.frame.FrameStaticProperties;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
import org.photonvision.vision.pipe.impl.FindBoardCornersPipe.FindBoardCornersPipeResult;
|
||||
|
||||
public class Calibrate3dPipe
|
||||
extends CVPipe<
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult>,
|
||||
Calibrate3dPipe.CalibrationInput,
|
||||
CameraCalibrationCoefficients,
|
||||
Calibrate3dPipe.CalibratePipeParams> {
|
||||
public static class CalibrationInput {
|
||||
final List<FindBoardCornersPipe.FindBoardCornersPipeResult> observations;
|
||||
final FrameStaticProperties imageProps;
|
||||
|
||||
public CalibrationInput(
|
||||
List<FindBoardCornersPipeResult> observations, FrameStaticProperties imageProps) {
|
||||
this.observations = observations;
|
||||
this.imageProps = imageProps;
|
||||
}
|
||||
}
|
||||
|
||||
// For logging
|
||||
private static final Logger logger = new Logger(Calibrate3dPipe.class, LogGroup.General);
|
||||
|
||||
@@ -63,10 +76,9 @@ public class Calibrate3dPipe
|
||||
* @return Result of processing.
|
||||
*/
|
||||
@Override
|
||||
protected CameraCalibrationCoefficients process(
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in) {
|
||||
in =
|
||||
in.stream()
|
||||
protected CameraCalibrationCoefficients process(CalibrationInput in) {
|
||||
var filteredIn =
|
||||
in.observations.stream()
|
||||
.filter(
|
||||
it ->
|
||||
it != null
|
||||
@@ -79,17 +91,21 @@ public class Calibrate3dPipe
|
||||
var start = System.nanoTime();
|
||||
if (MrCalJNILoader.getInstance().isLoaded() && params.useMrCal) {
|
||||
logger.debug("Calibrating with mrcal!");
|
||||
ret = calibrateMrcal(in);
|
||||
ret =
|
||||
calibrateMrcal(
|
||||
filteredIn, in.imageProps.horizontalFocalLength, in.imageProps.verticalFocalLength);
|
||||
} else {
|
||||
logger.debug("Calibrating with opencv!");
|
||||
ret = calibrateOpenCV(in);
|
||||
ret =
|
||||
calibrateOpenCV(
|
||||
filteredIn, in.imageProps.horizontalFocalLength, in.imageProps.verticalFocalLength);
|
||||
}
|
||||
var dt = System.nanoTime() - start;
|
||||
|
||||
if (ret != null)
|
||||
logger.info(
|
||||
"CALIBRATION SUCCESS for res "
|
||||
+ in.get(0).size
|
||||
+ in.observations.get(0).size
|
||||
+ " in "
|
||||
+ dt / 1e6
|
||||
+ "ms! camMatrix: \n"
|
||||
@@ -103,7 +119,7 @@ public class Calibrate3dPipe
|
||||
}
|
||||
|
||||
protected CameraCalibrationCoefficients calibrateOpenCV(
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in) {
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in, double fxGuess, double fyGuess) {
|
||||
List<Mat> objPoints = in.stream().map(it -> it.objectPoints).collect(Collectors.toList());
|
||||
List<Mat> imgPts = in.stream().map(it -> it.imagePoints).collect(Collectors.toList());
|
||||
if (objPoints.size() != imgPts.size()) {
|
||||
@@ -111,30 +127,32 @@ public class Calibrate3dPipe
|
||||
return null;
|
||||
}
|
||||
|
||||
Mat cameraMatrix = new Mat();
|
||||
Mat cameraMatrix = new Mat(3, 3, CvType.CV_64F);
|
||||
MatOfDouble distortionCoefficients = new MatOfDouble();
|
||||
List<Mat> rvecs = new ArrayList<>();
|
||||
List<Mat> tvecs = new ArrayList<>();
|
||||
|
||||
// RMS of the calibration
|
||||
double calibrationAccuracy;
|
||||
// initial camera matrix guess
|
||||
double cx = (in.get(0).size.width / 2.0) - 0.5;
|
||||
double cy = (in.get(0).size.width / 2.0) - 0.5;
|
||||
cameraMatrix.put(0, 0, new double[] {fxGuess, 0, cx, 0, fyGuess, cy, 0, 0, 1});
|
||||
|
||||
try {
|
||||
// FindBoardCorners pipe outputs all the image points, object points, and frames to calculate
|
||||
// imageSize from, other parameters are output Mats
|
||||
|
||||
calibrationAccuracy =
|
||||
Calib3d.calibrateCameraExtended(
|
||||
objPoints,
|
||||
imgPts,
|
||||
new Size(in.get(0).size.width, in.get(0).size.height),
|
||||
cameraMatrix,
|
||||
distortionCoefficients,
|
||||
rvecs,
|
||||
tvecs,
|
||||
stdDeviationsIntrinsics,
|
||||
stdDeviationsExtrinsics,
|
||||
perViewErrors);
|
||||
Calib3d.calibrateCameraExtended(
|
||||
objPoints,
|
||||
imgPts,
|
||||
new Size(in.get(0).size.width, in.get(0).size.height),
|
||||
cameraMatrix,
|
||||
distortionCoefficients,
|
||||
rvecs,
|
||||
tvecs,
|
||||
stdDeviationsIntrinsics,
|
||||
stdDeviationsExtrinsics,
|
||||
perViewErrors,
|
||||
Calib3d.CALIB_USE_LU + Calib3d.CALIB_USE_INTRINSIC_GUESS);
|
||||
} catch (Exception e) {
|
||||
logger.error("Calibration failed!", e);
|
||||
e.printStackTrace();
|
||||
@@ -164,13 +182,12 @@ public class Calibrate3dPipe
|
||||
}
|
||||
|
||||
protected CameraCalibrationCoefficients calibrateMrcal(
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in) {
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in, double fxGuess, double fyGuess) {
|
||||
List<MatOfPoint2f> corner_locations =
|
||||
in.stream().map(it -> it.imagePoints).map(MatOfPoint2f::new).collect(Collectors.toList());
|
||||
|
||||
int imageWidth = (int) in.get(0).size.width;
|
||||
int imageHeight = (int) in.get(0).size.height;
|
||||
final double FOCAL_LENGTH_GUESS = 1200;
|
||||
|
||||
MrCalResult result =
|
||||
MrCalJNI.calibrateCamera(
|
||||
@@ -180,7 +197,7 @@ public class Calibrate3dPipe
|
||||
params.squareSize,
|
||||
imageWidth,
|
||||
imageHeight,
|
||||
FOCAL_LENGTH_GUESS);
|
||||
(fxGuess + fyGuess) / 2.0);
|
||||
|
||||
// intrinsics are fx fy cx cy from mrcal
|
||||
JsonMatOfDouble cameraMatrixMat =
|
||||
|
||||
@@ -36,6 +36,7 @@ import org.photonvision.vision.frame.FrameThresholdType;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.ImageRotationMode;
|
||||
import org.photonvision.vision.pipe.CVPipe.CVPipeResult;
|
||||
import org.photonvision.vision.pipe.impl.Calibrate3dPipe.CalibrationInput;
|
||||
import org.photonvision.vision.pipe.impl.FindBoardCornersPipe.FindBoardCornersPipeResult;
|
||||
import org.photonvision.vision.pipeline.CVPipeline;
|
||||
import org.photonvision.vision.pipeline.Calibration3dPipelineSettings;
|
||||
@@ -176,7 +177,8 @@ public class Calibrate3dPipeline
|
||||
|
||||
/*Pass the board corners to the pipe, which will check again to see if all boards are valid
|
||||
and returns the corresponding image and object points*/
|
||||
calibrationOutput = calibrate3dPipe.run(foundCornersList);
|
||||
calibrationOutput =
|
||||
calibrate3dPipe.run(new CalibrationInput(foundCornersList, frameStaticProperties));
|
||||
|
||||
this.calibrating = false;
|
||||
|
||||
@@ -229,4 +231,9 @@ public class Calibrate3dPipeline
|
||||
public CameraCalibrationCoefficients cameraCalibrationCoefficients() {
|
||||
return calibrationOutput.output;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
// we never actually need to give resources up since pipelinemanager only makes one of us
|
||||
}
|
||||
}
|
||||
|
||||
@@ -41,7 +41,7 @@ public class FilterObjectDetectionsPipe
|
||||
}
|
||||
|
||||
private void filterContour(NeuralNetworkPipeResult contour) {
|
||||
var boc = contour.box;
|
||||
var boc = contour.bbox;
|
||||
|
||||
// Area filtering
|
||||
double areaPercentage = boc.area() / params.getFrameStaticProperties().imageArea * 100.0;
|
||||
|
||||
@@ -20,13 +20,13 @@ package org.photonvision.vision.pipe.impl;
|
||||
import org.opencv.core.Rect2d;
|
||||
|
||||
public class NeuralNetworkPipeResult {
|
||||
public NeuralNetworkPipeResult(Rect2d box2, Integer classIdx, Float confidence) {
|
||||
box = box2;
|
||||
public NeuralNetworkPipeResult(Rect2d boundingBox, int classIdx, double confidence) {
|
||||
bbox = boundingBox;
|
||||
this.classIdx = classIdx;
|
||||
this.confidence = confidence;
|
||||
}
|
||||
|
||||
public final int classIdx;
|
||||
public final Rect2d box;
|
||||
public final Rect2d bbox;
|
||||
public final double confidence;
|
||||
}
|
||||
|
||||
@@ -17,8 +17,17 @@
|
||||
|
||||
package org.photonvision.vision.pipe.impl;
|
||||
|
||||
import java.awt.Color;
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import org.opencv.core.Core;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.Rect2d;
|
||||
import org.opencv.core.Scalar;
|
||||
import org.opencv.core.Size;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
import org.photonvision.common.configuration.NeuralNetworkModelManager;
|
||||
import org.photonvision.common.util.ColorHelper;
|
||||
import org.photonvision.jni.RknnDetectorJNI.RknnObjectDetector;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
@@ -30,12 +39,27 @@ public class RknnDetectionPipe
|
||||
private RknnObjectDetector detector;
|
||||
|
||||
public RknnDetectionPipe() {
|
||||
// For now this is hard-coded to defaults. Should be refactored into set pipe params, though.
|
||||
// And ideally a little wrapper helper for only changing native stuff on content change created.
|
||||
// For now this is hard-coded to defaults. Should be refactored into set pipe
|
||||
// params, though.
|
||||
// And ideally a little wrapper helper for only changing native stuff on content
|
||||
// change created.
|
||||
this.detector =
|
||||
new RknnObjectDetector(
|
||||
NeuralNetworkModelManager.getInstance().getDefaultRknnModel().getAbsolutePath(),
|
||||
NeuralNetworkModelManager.getInstance().getLabels());
|
||||
NeuralNetworkModelManager.getInstance().getLabels(),
|
||||
NeuralNetworkModelManager.getInstance().getModelVersion());
|
||||
}
|
||||
|
||||
private static class Letterbox {
|
||||
double dx;
|
||||
double dy;
|
||||
double scale;
|
||||
|
||||
public Letterbox(double dx, double dy, double scale) {
|
||||
this.dx = dx;
|
||||
this.dy = dy;
|
||||
this.scale = scale;
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -47,7 +71,66 @@ public class RknnDetectionPipe
|
||||
return List.of();
|
||||
}
|
||||
|
||||
return detector.detect(in, params.nms, params.confidence);
|
||||
// letterbox
|
||||
var letterboxed = new Mat();
|
||||
var scale =
|
||||
letterbox(frame, letterboxed, new Size(640, 640), ColorHelper.colorToScalar(Color.GRAY));
|
||||
|
||||
if (letterboxed.width() != 640 || letterboxed.height() != 640) {
|
||||
// huh whack give up lol
|
||||
throw new RuntimeException("RGA bugged but still wrong size");
|
||||
}
|
||||
var ret = detector.detect(letterboxed, params.nms, params.confidence);
|
||||
|
||||
return resizeDetections(ret, scale);
|
||||
}
|
||||
|
||||
private List<NeuralNetworkPipeResult> resizeDetections(
|
||||
List<NeuralNetworkPipeResult> unscaled, Letterbox letterbox) {
|
||||
var ret = new ArrayList<NeuralNetworkPipeResult>();
|
||||
|
||||
for (var t : unscaled) {
|
||||
var scale = 1.0 / letterbox.scale;
|
||||
var boundingBox = t.bbox;
|
||||
double x = (boundingBox.x - letterbox.dx) * scale;
|
||||
double y = (boundingBox.y - letterbox.dy) * scale;
|
||||
double width = boundingBox.width * scale;
|
||||
double height = boundingBox.height * scale;
|
||||
|
||||
ret.add(
|
||||
new NeuralNetworkPipeResult(new Rect2d(x, y, width, height), t.classIdx, t.confidence));
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
private static Letterbox letterbox(Mat frame, Mat letterboxed, Size newShape, Scalar color) {
|
||||
// from https://github.com/ultralytics/yolov5/issues/8427#issuecomment-1172469631
|
||||
var frameSize = frame.size();
|
||||
var r = Math.min(newShape.height / frameSize.height, newShape.width / frameSize.width);
|
||||
|
||||
var newUnpad = new Size(Math.round(frameSize.width * r), Math.round(frameSize.height * r));
|
||||
|
||||
if (!(frameSize.equals(newUnpad))) {
|
||||
Imgproc.resize(frame, letterboxed, newUnpad, Imgproc.INTER_LINEAR);
|
||||
} else {
|
||||
frame.copyTo(letterboxed);
|
||||
}
|
||||
|
||||
var dw = newShape.width - newUnpad.width;
|
||||
var dh = newShape.height - newUnpad.height;
|
||||
|
||||
dw /= 2;
|
||||
dh /= 2;
|
||||
|
||||
int top = (int) (Math.round(dh - 0.1f));
|
||||
int bottom = (int) (Math.round(dh + 0.1f));
|
||||
int left = (int) (Math.round(dw - 0.1f));
|
||||
int right = (int) (Math.round(dw + 0.1f));
|
||||
Core.copyMakeBorder(
|
||||
letterboxed, letterboxed, top, bottom, left, right, Core.BORDER_CONSTANT, color);
|
||||
|
||||
return new Letterbox(dw, dh, r);
|
||||
}
|
||||
|
||||
public static class RknnDetectionPipeParams {
|
||||
|
||||
@@ -221,4 +221,11 @@ public class AprilTagPipeline extends CVPipeline<CVPipelineResult, AprilTagPipel
|
||||
|
||||
return new CVPipelineResult(sumPipeNanosElapsed, fps, targetList, multiTagResult, frame);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
aprilTagDetectionPipe.release();
|
||||
singleTagPoseEstimatorPipe.release();
|
||||
super.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -60,8 +60,8 @@ import org.photonvision.vision.target.TrackedTarget;
|
||||
import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters;
|
||||
|
||||
public class ArucoPipeline extends CVPipeline<CVPipelineResult, ArucoPipelineSettings> {
|
||||
private final ArucoDetectionPipe arucoDetectionPipe = new ArucoDetectionPipe();
|
||||
private final ArucoPoseEstimatorPipe singleTagPoseEstimatorPipe = new ArucoPoseEstimatorPipe();
|
||||
private ArucoDetectionPipe arucoDetectionPipe = new ArucoDetectionPipe();
|
||||
private ArucoPoseEstimatorPipe singleTagPoseEstimatorPipe = new ArucoPoseEstimatorPipe();
|
||||
private final MultiTargetPNPPipe multiTagPNPPipe = new MultiTargetPNPPipe();
|
||||
private final CalculateFPSPipe calculateFPSPipe = new CalculateFPSPipe();
|
||||
|
||||
@@ -250,4 +250,13 @@ public class ArucoPipeline extends CVPipeline<CVPipelineResult, ArucoPipelineSet
|
||||
windowSize,
|
||||
constant);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
arucoDetectionPipe.release();
|
||||
singleTagPoseEstimatorPipe.release();
|
||||
arucoDetectionPipe = null;
|
||||
singleTagPoseEstimatorPipe = null;
|
||||
super.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -34,6 +34,9 @@ public abstract class CVPipeline<R extends CVPipelineResult, S extends CVPipelin
|
||||
|
||||
private final FrameThresholdType thresholdType;
|
||||
|
||||
// So releaseable doesn't keep track of if we double-free something. so (ew) remember that here
|
||||
protected volatile boolean released = false;
|
||||
|
||||
public CVPipeline(FrameThresholdType thresholdType) {
|
||||
this.thresholdType = thresholdType;
|
||||
}
|
||||
@@ -64,6 +67,9 @@ public abstract class CVPipeline<R extends CVPipelineResult, S extends CVPipelin
|
||||
}
|
||||
|
||||
public R run(Frame frame, QuirkyCamera cameraQuirks) {
|
||||
if (released) {
|
||||
throw new RuntimeException("Pipeline use-after-free!");
|
||||
}
|
||||
if (settings == null) {
|
||||
throw new RuntimeException("No settings provided for pipeline!");
|
||||
}
|
||||
@@ -85,5 +91,7 @@ public abstract class CVPipeline<R extends CVPipelineResult, S extends CVPipelin
|
||||
* switch. Stubbed out, but override if needed.
|
||||
*/
|
||||
@Override
|
||||
public void release() {}
|
||||
public void release() {
|
||||
released = true;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -88,4 +88,9 @@ public class DriverModePipeline
|
||||
fps,
|
||||
new Frame(frame.processedImage, frame.colorImage, frame.type, frame.frameStaticProperties));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
// we never actually need to give resources up since pipelinemanager only makes one of us
|
||||
}
|
||||
}
|
||||
|
||||
@@ -131,5 +131,6 @@ public class ObjectDetectionPipeline
|
||||
@Override
|
||||
public void release() {
|
||||
rknnPipe.release();
|
||||
super.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,57 @@
|
||||
/*
|
||||
* Copyright (C) Photon Vision.
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
package org.photonvision.vision.processes;
|
||||
|
||||
import java.util.List;
|
||||
import org.photonvision.vision.camera.CameraType;
|
||||
|
||||
public class CameraMatchingOptions {
|
||||
public CameraMatchingOptions(
|
||||
boolean checkUSBPath,
|
||||
boolean checkVidPid,
|
||||
boolean checkBaseName,
|
||||
boolean checkPath,
|
||||
CameraType... allowedTypes) {
|
||||
this.checkUSBPath = checkUSBPath;
|
||||
this.checkVidPid = checkVidPid;
|
||||
this.checkBaseName = checkBaseName;
|
||||
this.checkPath = checkPath;
|
||||
this.allowedTypes = List.of(allowedTypes);
|
||||
}
|
||||
|
||||
public final boolean checkUSBPath;
|
||||
public final boolean checkVidPid;
|
||||
public final boolean checkBaseName;
|
||||
public final boolean checkPath;
|
||||
public final List<CameraType> allowedTypes;
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return "CameraMatchingOptions [checkUSBPath="
|
||||
+ checkUSBPath
|
||||
+ ", checkVidPid="
|
||||
+ checkVidPid
|
||||
+ ", checkBaseName="
|
||||
+ checkBaseName
|
||||
+ ", checkPath="
|
||||
+ checkPath
|
||||
+ ", allowedTypes="
|
||||
+ allowedTypes
|
||||
+ "]";
|
||||
}
|
||||
}
|
||||
@@ -61,7 +61,8 @@ public class PipelineManager {
|
||||
PipelineManager(
|
||||
DriverModePipelineSettings driverSettings,
|
||||
List<CVPipelineSettings> userPipelines,
|
||||
String uniqueName) {
|
||||
String uniqueName,
|
||||
int defaultIndex) {
|
||||
this.userPipelineSettings = new ArrayList<>(userPipelines);
|
||||
// This is to respect the default res idx for vendor cameras
|
||||
|
||||
@@ -70,10 +71,19 @@ public class PipelineManager {
|
||||
if (userPipelines.isEmpty()) addPipeline(PipelineType.Reflective);
|
||||
|
||||
calibration3dPipeline = new Calibrate3dPipeline(uniqueName);
|
||||
|
||||
// We know that at this stage, VisionRunner hasn't yet started so we're good to do this from
|
||||
// this thread
|
||||
this.setIndex(defaultIndex);
|
||||
updatePipelineFromRequested();
|
||||
}
|
||||
|
||||
public PipelineManager(CameraConfiguration config) {
|
||||
this(config.driveModeSettings, config.pipelineSettings, config.uniqueName);
|
||||
this(
|
||||
config.driveModeSettings,
|
||||
config.pipelineSettings,
|
||||
config.uniqueName,
|
||||
config.currentPipelineIndex);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -148,6 +158,7 @@ public class PipelineManager {
|
||||
* @return The currently active pipeline.
|
||||
*/
|
||||
public CVPipeline getCurrentPipeline() {
|
||||
updatePipelineFromRequested();
|
||||
if (currentPipelineIndex < 0) {
|
||||
switch (currentPipelineIndex) {
|
||||
case CAL_3D_INDEX:
|
||||
@@ -170,6 +181,16 @@ public class PipelineManager {
|
||||
return getPipelineSettings(currentPipelineIndex);
|
||||
}
|
||||
|
||||
private volatile int requestedIndex = 0;
|
||||
|
||||
/**
|
||||
* Grab the currently requested pipeline index. The VisionRunner may not have changed over to this
|
||||
* pipeline yet.
|
||||
*/
|
||||
public int getRequestedIndex() {
|
||||
return requestedIndex;
|
||||
}
|
||||
|
||||
/**
|
||||
* Internal method for setting the active pipeline. <br>
|
||||
* <br>
|
||||
@@ -179,6 +200,22 @@ public class PipelineManager {
|
||||
* @param newIndex Index of pipeline to be active
|
||||
*/
|
||||
private void setPipelineInternal(int newIndex) {
|
||||
requestedIndex = newIndex;
|
||||
}
|
||||
|
||||
/**
|
||||
* Based on a requested pipeline index, create/destroy pipelines as necessary. We do this as a
|
||||
* side effect of the main thread that calls getCurrentPipeline to avoid race conditions between
|
||||
* server threads and the VisionRunner TODO: this should be refactored. Shame Java doesn't have
|
||||
* RAII
|
||||
*/
|
||||
private void updatePipelineFromRequested() {
|
||||
int newIndex = requestedIndex;
|
||||
if (newIndex == currentPipelineIndex) {
|
||||
// nothing to do, probably no change -- give up
|
||||
return;
|
||||
}
|
||||
|
||||
if (newIndex < 0 && currentPipelineIndex >= 0) {
|
||||
// Transitioning to a built-in pipe, save off the current user one
|
||||
lastUserPipelineIdx = currentPipelineIndex;
|
||||
@@ -189,8 +226,8 @@ public class PipelineManager {
|
||||
return;
|
||||
}
|
||||
|
||||
// Cleanup potential old native resources before swapping over
|
||||
if (currentUserPipeline != null) {
|
||||
// Cleanup potential old native resources before swapping over for user pipelines
|
||||
if (currentUserPipeline != null && !(newIndex < 0)) {
|
||||
currentUserPipeline.release();
|
||||
}
|
||||
|
||||
|
||||
@@ -26,6 +26,7 @@ import java.util.HashMap;
|
||||
import java.util.LinkedList;
|
||||
import java.util.List;
|
||||
import java.util.function.BiConsumer;
|
||||
import java.util.stream.Collectors;
|
||||
import org.opencv.core.Size;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
@@ -142,7 +143,7 @@ public class VisionModule {
|
||||
ntConsumer =
|
||||
new NTDataPublisher(
|
||||
visionSource.getSettables().getConfiguration().nickname,
|
||||
pipelineManager::getCurrentPipelineIndex,
|
||||
pipelineManager::getRequestedIndex,
|
||||
this::setPipeline,
|
||||
pipelineManager::getDriverMode,
|
||||
this::setDriverMode);
|
||||
@@ -155,6 +156,7 @@ public class VisionModule {
|
||||
(result) ->
|
||||
lastPipelineResultBestTarget = result.hasTargets() ? result.targets.get(0) : null);
|
||||
|
||||
// Sync VisionModule state with the first pipeline index
|
||||
setPipeline(visionSource.getSettables().getConfiguration().currentPipelineIndex);
|
||||
|
||||
// Set vendor FOV
|
||||
@@ -320,7 +322,7 @@ public class VisionModule {
|
||||
|
||||
void changePipelineType(int newType) {
|
||||
pipelineManager.changePipelineType(newType);
|
||||
setPipeline(pipelineManager.getCurrentPipelineIndex());
|
||||
setPipeline(pipelineManager.getRequestedIndex());
|
||||
saveAndBroadcastAll();
|
||||
}
|
||||
|
||||
@@ -328,9 +330,7 @@ public class VisionModule {
|
||||
pipelineManager.setDriverMode(isDriverMode);
|
||||
setVisionLEDs(!isDriverMode);
|
||||
setPipeline(
|
||||
isDriverMode
|
||||
? PipelineManager.DRIVERMODE_INDEX
|
||||
: pipelineManager.getCurrentPipelineIndex());
|
||||
isDriverMode ? PipelineManager.DRIVERMODE_INDEX : pipelineManager.getRequestedIndex());
|
||||
saveAndBroadcastAll();
|
||||
}
|
||||
|
||||
@@ -384,7 +384,7 @@ public class VisionModule {
|
||||
var ret = pipelineManager.calibration3dPipeline.tryCalibration();
|
||||
pipelineManager.setCalibrationMode(false);
|
||||
|
||||
setPipeline(pipelineManager.getCurrentPipelineIndex());
|
||||
setPipeline(pipelineManager.getRequestedIndex());
|
||||
|
||||
if (ret != null) {
|
||||
logger.debug("Saving calibration...");
|
||||
@@ -446,7 +446,7 @@ public class VisionModule {
|
||||
setVisionLEDs(pipelineSettings.ledMode);
|
||||
|
||||
visionSource.getSettables().getConfiguration().currentPipelineIndex =
|
||||
pipelineManager.getCurrentPipelineIndex();
|
||||
pipelineManager.getRequestedIndex();
|
||||
|
||||
return true;
|
||||
}
|
||||
@@ -510,7 +510,7 @@ public class VisionModule {
|
||||
ret.uniqueName = visionSource.getSettables().getConfiguration().uniqueName;
|
||||
ret.currentPipelineSettings =
|
||||
SerializationUtils.objectToHashMap(pipelineManager.getCurrentPipelineSettings());
|
||||
ret.currentPipelineIndex = pipelineManager.getCurrentPipelineIndex();
|
||||
ret.currentPipelineIndex = pipelineManager.getRequestedIndex();
|
||||
ret.pipelineNicknames = pipelineManager.getPipelineNicknames();
|
||||
ret.cameraQuirks = visionSource.getSettables().getConfiguration().cameraQuirks;
|
||||
|
||||
@@ -536,7 +536,10 @@ public class VisionModule {
|
||||
ret.outputStreamPort = this.outputStreamPort;
|
||||
ret.inputStreamPort = this.inputStreamPort;
|
||||
|
||||
ret.calibrations = visionSource.getSettables().getConfiguration().calibrations;
|
||||
ret.calibrations =
|
||||
visionSource.getSettables().getConfiguration().calibrations.stream()
|
||||
.map(CameraCalibrationCoefficients::cloneWithoutObservations)
|
||||
.collect(Collectors.toList());
|
||||
|
||||
ret.isFovConfigurable =
|
||||
!(ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV()
|
||||
@@ -549,7 +552,7 @@ public class VisionModule {
|
||||
var config = visionSource.getSettables().getConfiguration();
|
||||
config.setPipelineSettings(pipelineManager.userPipelineSettings);
|
||||
config.driveModeSettings = pipelineManager.driverModePipeline.getSettings();
|
||||
config.currentPipelineIndex = Math.max(pipelineManager.getCurrentPipelineIndex(), -1);
|
||||
config.currentPipelineIndex = Math.max(pipelineManager.getRequestedIndex(), -1);
|
||||
|
||||
return config;
|
||||
}
|
||||
|
||||
@@ -88,7 +88,7 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber {
|
||||
parentModule.saveAndBroadcastAll();
|
||||
return;
|
||||
case "deleteCurrPipeline":
|
||||
var indexToDelete = parentModule.pipelineManager.getCurrentPipelineIndex();
|
||||
var indexToDelete = parentModule.pipelineManager.getRequestedIndex();
|
||||
logger.info("Deleting current pipe at index " + indexToDelete);
|
||||
int newIndex = parentModule.pipelineManager.removePipeline(indexToDelete);
|
||||
parentModule.setPipeline(newIndex);
|
||||
@@ -96,7 +96,7 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber {
|
||||
return;
|
||||
case "changePipeline": // change active pipeline
|
||||
var index = (Integer) newPropValue;
|
||||
if (index == parentModule.pipelineManager.getCurrentPipelineIndex()) {
|
||||
if (index == parentModule.pipelineManager.getRequestedIndex()) {
|
||||
logger.debug("Skipping pipeline change, index " + index + " already active");
|
||||
return;
|
||||
}
|
||||
@@ -181,6 +181,9 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber {
|
||||
parentModule.changePipelineType((Integer) newPropValue);
|
||||
parentModule.saveAndBroadcastAll();
|
||||
return;
|
||||
case "isDriverMode":
|
||||
parentModule.setDriverMode((Boolean) newPropValue);
|
||||
return;
|
||||
}
|
||||
|
||||
// special case for camera settables
|
||||
|
||||
@@ -23,6 +23,7 @@ import java.util.Arrays;
|
||||
import java.util.Collection;
|
||||
import java.util.List;
|
||||
import java.util.concurrent.CopyOnWriteArrayList;
|
||||
import java.util.function.Predicate;
|
||||
import java.util.stream.Collectors;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
@@ -38,6 +39,7 @@ import org.photonvision.vision.camera.CameraInfo;
|
||||
import org.photonvision.vision.camera.CameraQuirk;
|
||||
import org.photonvision.vision.camera.CameraType;
|
||||
import org.photonvision.vision.camera.LibcameraGpuSource;
|
||||
import org.photonvision.vision.camera.TestSource;
|
||||
import org.photonvision.vision.camera.USBCameraSource;
|
||||
|
||||
public class VisionSourceManager {
|
||||
@@ -145,8 +147,8 @@ public class VisionSourceManager {
|
||||
}
|
||||
|
||||
// Return no new sources because there are no new sources
|
||||
if (connectedCameras.isEmpty() && !cameraInfos.isEmpty()) {
|
||||
if (hasWarnedNoCameras) {
|
||||
if (connectedCameras.isEmpty()) {
|
||||
if (!hasWarnedNoCameras) {
|
||||
logger.warn(
|
||||
"No cameras were detected! Check that all cameras are connected, and that the path is correct.");
|
||||
hasWarnedNoCameras = true;
|
||||
@@ -164,7 +166,7 @@ public class VisionSourceManager {
|
||||
|
||||
// Debug prints
|
||||
for (var info : connectedCameras) {
|
||||
logger.info("Adding local video device - \"" + info.name + "\" at \"" + info.path + "\"");
|
||||
logger.info("Detected unmatched physical camera: " + info.toString());
|
||||
}
|
||||
|
||||
if (!unmatchedLoadedConfigs.isEmpty())
|
||||
@@ -185,7 +187,7 @@ public class VisionSourceManager {
|
||||
"Unloaded configs: "
|
||||
+ unmatchedLoadedConfigs.stream()
|
||||
.map(it -> it.nickname)
|
||||
.collect(Collectors.joining()));
|
||||
.collect(Collectors.joining(", ")));
|
||||
hasWarned = true;
|
||||
}
|
||||
|
||||
@@ -194,13 +196,8 @@ public class VisionSourceManager {
|
||||
|
||||
if (matchedCameras.isEmpty()) return null;
|
||||
|
||||
// for unit tests only!
|
||||
if (!createSources) {
|
||||
return List.of();
|
||||
}
|
||||
|
||||
// Turn these camera configs into vision sources
|
||||
var sources = loadVisionSourcesFromCamConfigs(matchedCameras);
|
||||
var sources = loadVisionSourcesFromCamConfigs(matchedCameras, createSources);
|
||||
|
||||
// Print info about each vision source
|
||||
for (var src : sources) {
|
||||
@@ -216,6 +213,54 @@ public class VisionSourceManager {
|
||||
return sources;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get a predicate for checking cameras against a saved config.
|
||||
*
|
||||
* @param savedConfig The saved camera configuration to match against
|
||||
* @param checkUSBPath If we should compare the USB port/bus IDs
|
||||
* @param checkVidPid If we should compare USB VID and PID
|
||||
* @param checkBaseName If we should compare {@link CameraInfo#getBaseName}
|
||||
* @param checkPath If we should check {@link CameraInfo::path} (eg /dev/videoN on Linux, or
|
||||
* ?/usb#vid_05c8&pid_03df&mi_00#7&fa76035&0&0000#{e5323777-f976-4f5b-9b55-b94699c46e44}\global
|
||||
* on Windows)
|
||||
*/
|
||||
private final Predicate<CameraInfo> getCameraMatcher(
|
||||
final CameraConfiguration savedConfig,
|
||||
boolean checkUSBPath,
|
||||
boolean checkVidPid,
|
||||
boolean checkBaseName,
|
||||
boolean checkPath) {
|
||||
if (checkUSBPath && savedConfig.getUSBPath().isEmpty()) {
|
||||
logger.debug(
|
||||
"WARN: Camera has empty USB path, but asked to match by name: "
|
||||
+ camCfgToString(savedConfig));
|
||||
}
|
||||
|
||||
return (CameraInfo physicalCamera) -> {
|
||||
var matches = true;
|
||||
|
||||
if (checkUSBPath) {
|
||||
var savedPath = savedConfig.getUSBPath();
|
||||
matches &= (savedPath.isPresent() && physicalCamera.getUSBPath().equals(savedPath));
|
||||
}
|
||||
if (checkBaseName) {
|
||||
matches &= physicalCamera.getBaseName().equals(savedConfig.baseName);
|
||||
}
|
||||
if (checkVidPid) {
|
||||
matches &=
|
||||
(physicalCamera.vendorId == savedConfig.usbVID
|
||||
&& physicalCamera.productId == savedConfig.usbPID);
|
||||
}
|
||||
if (checkPath) {
|
||||
matches &= (physicalCamera.path.equals(savedConfig.path));
|
||||
}
|
||||
|
||||
matches &= (physicalCamera.cameraType == savedConfig.cameraType);
|
||||
|
||||
return matches;
|
||||
};
|
||||
}
|
||||
|
||||
/**
|
||||
* Create {@link CameraConfiguration}s based on a list of detected USB cameras and the configs on
|
||||
* disk.
|
||||
@@ -226,158 +271,212 @@ public class VisionSourceManager {
|
||||
*/
|
||||
public List<CameraConfiguration> matchCameras(
|
||||
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> loadedCamConfigs) {
|
||||
return matchCameras(
|
||||
detectedCamInfos,
|
||||
loadedCamConfigs,
|
||||
ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath);
|
||||
}
|
||||
|
||||
private static final String camCfgToString(CameraConfiguration c) {
|
||||
return new StringBuilder()
|
||||
.append("[baseName=")
|
||||
.append(c.baseName)
|
||||
.append(", uniqueName=")
|
||||
.append(c.uniqueName)
|
||||
.append(", otherPaths=")
|
||||
.append(Arrays.toString(c.otherPaths))
|
||||
.append(", vid=")
|
||||
.append(c.usbVID)
|
||||
.append(", pid=")
|
||||
.append(c.usbPID)
|
||||
.append("]")
|
||||
.toString();
|
||||
}
|
||||
|
||||
/**
|
||||
* Create {@link CameraConfiguration}s based on a list of detected USB cameras and the configs on
|
||||
* disk.
|
||||
*
|
||||
* @param detectedCamInfos Information about currently connected USB cameras.
|
||||
* @param loadedCamConfigs The USB {@link CameraConfiguration}s loaded from disk.
|
||||
* @param matchCamerasOnlyByPath If we should never try to match only by (base name, vid, pid)
|
||||
* @return the matched configurations.
|
||||
*/
|
||||
public List<CameraConfiguration> matchCameras(
|
||||
List<CameraInfo> detectedCamInfos,
|
||||
List<CameraConfiguration> loadedCamConfigs,
|
||||
boolean matchCamerasOnlyByPath) {
|
||||
var detectedCameraList = new ArrayList<>(detectedCamInfos);
|
||||
ArrayList<CameraConfiguration> cameraConfigurations = new ArrayList<CameraConfiguration>();
|
||||
ArrayList<CameraConfiguration> unloadedConfigs =
|
||||
new ArrayList<CameraConfiguration>(loadedCamConfigs);
|
||||
|
||||
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0)
|
||||
cameraConfigurations.addAll(matchByPathByID(detectedCameraList, unloadedConfigs));
|
||||
else logger.debug("Skipping matchByPath no configs or cameras left to match");
|
||||
logger.info("Matching CSI cameras by port & base name...");
|
||||
cameraConfigurations.addAll(
|
||||
matchCamerasByStrategy(
|
||||
detectedCameraList,
|
||||
unloadedConfigs,
|
||||
new CameraMatchingOptions(false, false, true, true, CameraType.ZeroCopyPicam)));
|
||||
|
||||
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0)
|
||||
cameraConfigurations.addAll(matchByPath(detectedCameraList, unloadedConfigs));
|
||||
else logger.debug("Skipping matchByPath no configs or cameras left to match");
|
||||
logger.info("Matching USB cameras by usb port & name & USB VID/PID...");
|
||||
cameraConfigurations.addAll(
|
||||
matchCamerasByStrategy(
|
||||
detectedCameraList,
|
||||
unloadedConfigs,
|
||||
new CameraMatchingOptions(true, true, true, false, CameraType.UsbCamera)));
|
||||
|
||||
if (detectedCameraList.size() > 0 || unloadedConfigs.size() > 0)
|
||||
cameraConfigurations.addAll(matchByName(detectedCameraList, unloadedConfigs));
|
||||
else logger.debug("Skipping matchByName no configs or cameras left to match");
|
||||
|
||||
if (detectedCameraList.size() > 0)
|
||||
// On windows, the v4l path is actually useful and tells us the port the camera is physically
|
||||
// connected to which is neat
|
||||
if (Platform.isWindows() && !matchCamerasOnlyByPath) {
|
||||
logger.info("Matching USB cameras by windows-path & USB VID/PID only...");
|
||||
cameraConfigurations.addAll(
|
||||
createConfigsForCameras(detectedCameraList, unloadedConfigs, cameraConfigurations));
|
||||
matchCamerasByStrategy(
|
||||
detectedCameraList,
|
||||
unloadedConfigs,
|
||||
new CameraMatchingOptions(false, true, true, true, CameraType.UsbCamera)));
|
||||
}
|
||||
|
||||
logger.info("Matching USB cameras by usb port & USB VID/PID...");
|
||||
cameraConfigurations.addAll(
|
||||
matchCamerasByStrategy(
|
||||
detectedCameraList,
|
||||
unloadedConfigs,
|
||||
new CameraMatchingOptions(true, true, false, false, CameraType.UsbCamera)));
|
||||
|
||||
// Legacy migration -- VID/PID will be unset, so we have to try with our most relaxed strategy
|
||||
// at least once. We _should_ still have a valid USB path (assuming cameras have not moved), so
|
||||
// try that first, then fallback to base name only beloow
|
||||
logger.info("Matching USB cameras by base-name & usb port...");
|
||||
cameraConfigurations.addAll(
|
||||
matchCamerasByStrategy(
|
||||
detectedCameraList,
|
||||
unloadedConfigs,
|
||||
new CameraMatchingOptions(true, false, true, false, CameraType.UsbCamera)));
|
||||
|
||||
// handle disabling only-by-base-name matching
|
||||
if (!matchCamerasOnlyByPath) {
|
||||
logger.info("Matching USB cameras by base-name & USB VID/PID only...");
|
||||
cameraConfigurations.addAll(
|
||||
matchCamerasByStrategy(
|
||||
detectedCameraList,
|
||||
unloadedConfigs,
|
||||
new CameraMatchingOptions(false, true, true, false, CameraType.UsbCamera)));
|
||||
|
||||
// Legacy migration for if no USB VID/PID set
|
||||
logger.info("Matching USB cameras by base-name only...");
|
||||
cameraConfigurations.addAll(
|
||||
matchCamerasByStrategy(
|
||||
detectedCameraList,
|
||||
unloadedConfigs,
|
||||
new CameraMatchingOptions(false, false, true, false, CameraType.UsbCamera)));
|
||||
} else logger.info("Skipping match by filepath/vid/pid, disabled by user");
|
||||
|
||||
if (detectedCameraList.size() > 0) {
|
||||
// handle disabling only-by-base-name matching
|
||||
if (!matchCamerasOnlyByPath) {
|
||||
cameraConfigurations.addAll(
|
||||
createConfigsForCameras(detectedCameraList, unloadedConfigs, cameraConfigurations));
|
||||
} else {
|
||||
logger.warn(
|
||||
"Not creating 'new' Photon CameraConfigurations for ["
|
||||
+ detectedCamInfos.stream()
|
||||
.map(CameraInfo::toString)
|
||||
.collect(Collectors.joining(";"))
|
||||
+ "], disabled by user");
|
||||
}
|
||||
}
|
||||
|
||||
logger.debug("Matched or created " + cameraConfigurations.size() + " camera configs!");
|
||||
return cameraConfigurations;
|
||||
}
|
||||
|
||||
// loop over all the configs loaded from disk, attempting to match each camera
|
||||
// to a config by path-by-id on linux
|
||||
private List<CameraConfiguration> matchByPathByID(
|
||||
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> unloadedConfigs) {
|
||||
/**
|
||||
* Abstractly match cameras
|
||||
*
|
||||
* @param detectedCamInfos Physical cameras unmatched and attached to the device
|
||||
* @param unloadedConfigs {@link CameraConfiguration}
|
||||
* @param checkUSBPath If we should compare the USB port/bus IDs
|
||||
* @param checkVidPid If we should compare USB VID and PID
|
||||
* @param checkBaseName If we should check {@link CameraInfo::getBaseName}
|
||||
* @param checkPath If we should check {@link CameraInfo::path} (eg /dev/videoN on Linux, or
|
||||
* usb#vid_05c8&pid_03df&mi_00#7&fa76035&0&0000#{e5323777-f976-4f5b-9b55-b94699c46e44}\global
|
||||
* on Windows). Note that path may change based on order cameras are plugged in/unplugged on
|
||||
* Linux, and should not be trusted to remain the same.
|
||||
* @return All matched or created new configs
|
||||
*/
|
||||
private List<CameraConfiguration> matchCamerasByStrategy(
|
||||
List<CameraInfo> detectedCamInfos,
|
||||
List<CameraConfiguration> unloadedConfigs,
|
||||
CameraMatchingOptions matchingOptions) {
|
||||
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
|
||||
List<CameraConfiguration> unloadedConfigsCopy =
|
||||
new ArrayList<CameraConfiguration>(unloadedConfigs);
|
||||
|
||||
for (CameraConfiguration config : unloadedConfigsCopy) {
|
||||
// Only run match path by id if the camera is not a CSI camera.
|
||||
if (config.cameraType != CameraType.ZeroCopyPicam) {
|
||||
CameraInfo cameraInfo;
|
||||
if (config.otherPaths.length == 0) {
|
||||
logger.debug("No valid path-by-id found for config with name " + config.baseName);
|
||||
} else {
|
||||
// attempt matching by path and basename
|
||||
logger.debug(
|
||||
"Trying to find a match for loaded camera "
|
||||
+ config.baseName
|
||||
+ " with path-by-id "
|
||||
+ config.otherPaths[0]);
|
||||
cameraInfo =
|
||||
detectedCamInfos.stream()
|
||||
.filter(
|
||||
usbCameraInfo ->
|
||||
usbCameraInfo.otherPaths.length != 0
|
||||
&& usbCameraInfo.otherPaths[0].equals(config.otherPaths[0])
|
||||
&& usbCameraInfo.getBaseName().equals(config.baseName))
|
||||
.findFirst()
|
||||
.orElse(null);
|
||||
if (unloadedConfigsCopy.isEmpty()) return List.of();
|
||||
|
||||
// If we actually matched a camera to a config, remove that camera from the list
|
||||
// and add it to the output
|
||||
if (cameraInfo != null) {
|
||||
logger.debug("Matched the config for " + config.baseName + " to a physical camera!");
|
||||
ret.add(mergeInfoIntoConfig(config, cameraInfo));
|
||||
detectedCamInfos.remove(cameraInfo);
|
||||
unloadedConfigs.remove(config);
|
||||
}
|
||||
logger.debug("Matching with options " + matchingOptions.toString());
|
||||
|
||||
for (CameraConfiguration config : unloadedConfigsCopy) {
|
||||
// Only run match path by id if the camera type is allowed. This allows us to specify matching
|
||||
// behavior per-camera-type
|
||||
if (matchingOptions.allowedTypes.contains(config.cameraType)) {
|
||||
logger.debug(
|
||||
String.format(
|
||||
"Trying to find a match for loaded camera %s (%s) with camera config: %s",
|
||||
config.baseName, config.uniqueName, camCfgToString(config)));
|
||||
|
||||
// Get matcher and filter against it, picking out the first match
|
||||
Predicate<CameraInfo> matches =
|
||||
getCameraMatcher(
|
||||
config,
|
||||
matchingOptions.checkUSBPath,
|
||||
matchingOptions.checkVidPid,
|
||||
matchingOptions.checkBaseName,
|
||||
matchingOptions.checkPath);
|
||||
var cameraInfo = detectedCamInfos.stream().filter(matches).findFirst().orElse(null);
|
||||
|
||||
// If we actually matched a camera to a config, remove that camera from the list
|
||||
// and add it to the output
|
||||
if (cameraInfo != null) {
|
||||
logger.debug(
|
||||
"Matched the config for "
|
||||
+ config.uniqueName
|
||||
+ " to the physical camera config above!");
|
||||
ret.add(mergeInfoIntoConfig(config, cameraInfo));
|
||||
detectedCamInfos.remove(cameraInfo);
|
||||
unloadedConfigs.remove(config);
|
||||
} else {
|
||||
logger.debug("No camera found for the config " + config.uniqueName);
|
||||
}
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
private List<CameraConfiguration> matchByPath(
|
||||
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> unloadedConfigs) {
|
||||
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
|
||||
List<CameraConfiguration> unloadedConfigsCopy =
|
||||
new ArrayList<CameraConfiguration>(unloadedConfigs);
|
||||
// now attempt to match the cameras and configs remaining by normal path
|
||||
for (CameraConfiguration config : unloadedConfigsCopy) {
|
||||
CameraInfo cameraInfo;
|
||||
|
||||
// attempt matching by path and basename
|
||||
logger.debug(
|
||||
"Trying to find a match for loaded camera "
|
||||
+ config.baseName
|
||||
+ " with path "
|
||||
+ config.path);
|
||||
cameraInfo =
|
||||
detectedCamInfos.stream()
|
||||
.filter(
|
||||
usbCameraInfo ->
|
||||
usbCameraInfo.path.equals(config.path)
|
||||
&& usbCameraInfo.getBaseName().equals(config.baseName))
|
||||
.findFirst()
|
||||
.orElse(null);
|
||||
|
||||
// If we actually matched a camera to a config, remove that camera from the list
|
||||
// and add it to the output
|
||||
if (cameraInfo != null) {
|
||||
logger.debug("Matched the config for " + config.baseName + " to a physical camera!");
|
||||
ret.add(mergeInfoIntoConfig(config, cameraInfo));
|
||||
detectedCamInfos.remove(cameraInfo);
|
||||
unloadedConfigs.remove(config);
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
// Try matching cameras to configs by name.
|
||||
private List<CameraConfiguration> matchByName(
|
||||
List<CameraInfo> detectedCamInfos, List<CameraConfiguration> unloadedConfigs) {
|
||||
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
|
||||
List<CameraConfiguration> unloadedConfigsCopy =
|
||||
new ArrayList<CameraConfiguration>(unloadedConfigs);
|
||||
// if both path and ID based matching fails, attempt basename only match
|
||||
for (CameraConfiguration config : unloadedConfigsCopy) {
|
||||
CameraInfo cameraInfo;
|
||||
|
||||
logger.debug("Trying to find a match for loaded camera with name " + config.baseName);
|
||||
|
||||
cameraInfo =
|
||||
detectedCamInfos.stream()
|
||||
.filter(CameraInfo -> CameraInfo.getBaseName().equals(config.baseName))
|
||||
.findFirst()
|
||||
.orElse(null);
|
||||
|
||||
// If we actually matched a camera to a config, remove that camera from the list
|
||||
// and add it to the output
|
||||
if (cameraInfo != null) {
|
||||
logger.debug("Matched the config for " + config.baseName + " to a physical camera!");
|
||||
ret.add(mergeInfoIntoConfig(config, cameraInfo));
|
||||
detectedCamInfos.remove(cameraInfo);
|
||||
unloadedConfigs.remove(config);
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
// If we have any unmatched cameras left, create a new CameraConfiguration for
|
||||
// them here.
|
||||
/**
|
||||
* Create new {@link CameraConfiguration}s for unmatched cameras, and assign them a unique name
|
||||
* (unique in the set of (loaded configs, unloaded configs, loaded vision modules) at least)
|
||||
*/
|
||||
private List<CameraConfiguration> createConfigsForCameras(
|
||||
List<CameraInfo> detectedCameraList,
|
||||
List<CameraConfiguration> loadedCamConfigs,
|
||||
List<CameraConfiguration> unloadedCamConfigs,
|
||||
List<CameraConfiguration> loadedConfigs) {
|
||||
List<CameraConfiguration> ret = new ArrayList<CameraConfiguration>();
|
||||
logger.debug(
|
||||
"After matching loaded configs " + detectedCameraList.size() + " cameras were unmatched.");
|
||||
"After matching loaded configs, these configs remained unmatched: "
|
||||
+ detectedCameraList.stream()
|
||||
.map(n -> String.valueOf(n))
|
||||
.collect(Collectors.joining("-", "{", "}")));
|
||||
for (CameraInfo info : detectedCameraList) {
|
||||
// create new camera config for all new cameras
|
||||
String baseName = info.getBaseName();
|
||||
String uniqueName = info.getHumanReadableName();
|
||||
|
||||
int suffix = 0;
|
||||
while (containsName(loadedConfigs, uniqueName) || containsName(uniqueName)) {
|
||||
while (containsName(loadedConfigs, uniqueName)
|
||||
|| containsName(uniqueName)
|
||||
|| containsName(unloadedCamConfigs, uniqueName)
|
||||
|| containsName(ret, uniqueName)) {
|
||||
suffix++;
|
||||
uniqueName = String.format("%s (%d)", uniqueName, suffix);
|
||||
}
|
||||
@@ -457,10 +556,16 @@ public class VisionSourceManager {
|
||||
}
|
||||
|
||||
private static List<VisionSource> loadVisionSourcesFromCamConfigs(
|
||||
List<CameraConfiguration> camConfigs) {
|
||||
List<CameraConfiguration> camConfigs, boolean createSources) {
|
||||
var cameraSources = new ArrayList<VisionSource>();
|
||||
for (var configuration : camConfigs) {
|
||||
logger.debug("Creating VisionSource for " + configuration);
|
||||
logger.debug("Creating VisionSource for " + camCfgToString(configuration));
|
||||
|
||||
// In unit tests, create dummy
|
||||
if (!createSources) {
|
||||
cameraSources.add(new TestSource(configuration));
|
||||
continue;
|
||||
}
|
||||
|
||||
boolean is_pi = Platform.isRaspberryPi();
|
||||
|
||||
|
||||
@@ -56,7 +56,7 @@ public class PotentialTarget implements Releasable {
|
||||
}
|
||||
|
||||
public PotentialTarget(NeuralNetworkPipeResult det) {
|
||||
this.shape = new CVShape(new Contour(det.box), ContourShape.Quadrilateral);
|
||||
this.shape = new CVShape(new Contour(det.bbox), ContourShape.Quadrilateral);
|
||||
this.m_mainContour = this.shape.getContour();
|
||||
m_subContours = List.of();
|
||||
this.clsId = det.classIdx;
|
||||
|
||||
@@ -139,8 +139,31 @@ public class ConfigTest {
|
||||
writer.write(str);
|
||||
writer.flush();
|
||||
writer.close();
|
||||
Assertions.assertDoesNotThrow(
|
||||
() -> JacksonUtils.deserialize(tempFile.toPath(), CameraConfiguration.class));
|
||||
CameraConfiguration result =
|
||||
JacksonUtils.deserialize(tempFile.toPath(), CameraConfiguration.class);
|
||||
|
||||
tempFile.delete();
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testJacksonAddUSBVIDPID() throws IOException {
|
||||
var str =
|
||||
"{\"baseName\":\"aaaaaa\",\"uniqueName\":\"aaaaaa\",\"nickname\":\"aaaaaa\",\"FOV\":70.0,\"path\":\"dev/vid\",\"cameraType\":\"UsbCamera\",\"currentPipelineIndex\":0,\"camPitch\":{\"radians\":0.0},\"calibrations\":[], \"usbVID\":3, \"usbPID\":4, \"cameraLEDs\":[]}";
|
||||
File tempFile = File.createTempFile("test", ".json");
|
||||
tempFile.deleteOnExit();
|
||||
var writer = new FileWriter(tempFile);
|
||||
writer.write(str);
|
||||
writer.flush();
|
||||
writer.close();
|
||||
|
||||
try {
|
||||
CameraConfiguration result =
|
||||
JacksonUtils.deserialize(tempFile.toPath(), CameraConfiguration.class);
|
||||
String ser = JacksonUtils.serializeToString(result);
|
||||
System.out.println(ser);
|
||||
} catch (Exception e) {
|
||||
e.printStackTrace();
|
||||
}
|
||||
|
||||
tempFile.delete();
|
||||
}
|
||||
|
||||
@@ -84,7 +84,9 @@ public class SQLConfigTest {
|
||||
CameraType.UsbCamera,
|
||||
QuirkyCamera.getQuirkyCamera(-1, -1),
|
||||
List.of(),
|
||||
0);
|
||||
0,
|
||||
-1,
|
||||
-1);
|
||||
testcamcfg.pipelineSettings =
|
||||
List.of(
|
||||
new ReflectivePipelineSettings(),
|
||||
|
||||
@@ -30,7 +30,7 @@ public class PipelineManagerTest {
|
||||
public void testUniqueName() {
|
||||
TestUtils.loadLibraries();
|
||||
PipelineManager manager =
|
||||
new PipelineManager(new DriverModePipelineSettings(), List.of(), "meme_name");
|
||||
new PipelineManager(new DriverModePipelineSettings(), List.of(), "meme_name", -1);
|
||||
manager.addPipeline(PipelineType.Reflective, "Another");
|
||||
|
||||
// We now have ["New Pipeline", "Another"]
|
||||
|
||||
@@ -21,17 +21,24 @@ import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.LogLevel;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.vision.camera.CameraInfo;
|
||||
import org.photonvision.vision.camera.CameraType;
|
||||
|
||||
public class VisionSourceManagerTest {
|
||||
@Test
|
||||
public void visionSourceTest() {
|
||||
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
|
||||
|
||||
var inst = new VisionSourceManager();
|
||||
var cameraInfos = new ArrayList<CameraInfo>();
|
||||
ConfigManager.getInstance().clearConfig();
|
||||
ConfigManager.getInstance().load();
|
||||
|
||||
inst.tryMatchCamImpl(cameraInfos);
|
||||
@@ -43,6 +50,8 @@ public class VisionSourceManagerTest {
|
||||
"thirdTestVideo",
|
||||
"dev/video1",
|
||||
new String[] {"by-id/123"});
|
||||
config3.usbVID = 3;
|
||||
config3.usbPID = 4;
|
||||
var config4 =
|
||||
new CameraConfiguration(
|
||||
"fourthTestVideo",
|
||||
@@ -50,6 +59,8 @@ public class VisionSourceManagerTest {
|
||||
"fourthTestVideo",
|
||||
"dev/video2",
|
||||
new String[] {"by-id/321"});
|
||||
config4.usbVID = 5;
|
||||
config4.usbPID = 6;
|
||||
|
||||
CameraInfo info1 = new CameraInfo(0, "dev/video0", "testVideo", new String[0], 1, 2);
|
||||
|
||||
@@ -261,4 +272,335 @@ public class VisionSourceManagerTest {
|
||||
assertEquals(10, inst.knownCameras.size());
|
||||
assertEquals(0, inst.unmatchedLoadedConfigs.size());
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testDisableInhibitPathChangeIdenticalCams() {
|
||||
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
|
||||
|
||||
var inst = new VisionSourceManager();
|
||||
ConfigManager.getInstance().clearConfig();
|
||||
ConfigManager.getInstance().load();
|
||||
ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = false;
|
||||
|
||||
var CAM2_OLD_PATH =
|
||||
new String[] {"/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"};
|
||||
var CAM2_NEW_PATH =
|
||||
new String[] {"/dev/v4l/by-path/platform-fc880080.usb-usb-0:1:1.3-video-index0"};
|
||||
|
||||
var CAM1_OLD_PATHS =
|
||||
new String[] {
|
||||
"/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
|
||||
"/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0"
|
||||
};
|
||||
|
||||
var camera1_saved_config =
|
||||
new CameraConfiguration(
|
||||
"Arducam OV2311 USB Camera",
|
||||
"Arducam OV2311 USB Camera",
|
||||
"fromt-left",
|
||||
"/dev/video0",
|
||||
CAM1_OLD_PATHS);
|
||||
camera1_saved_config.usbVID = 3141;
|
||||
camera1_saved_config.usbPID = 25446;
|
||||
var camera2_saved_config =
|
||||
new CameraConfiguration(
|
||||
"Arducam OV2311 USB Camera",
|
||||
"Arducam OV2311 USB Camera (1)",
|
||||
"fromt-left",
|
||||
"/dev/video2",
|
||||
CAM2_OLD_PATH);
|
||||
camera2_saved_config.usbVID = 3141;
|
||||
camera2_saved_config.usbPID = 25446;
|
||||
|
||||
// And load our "old" configs
|
||||
inst.registerLoadedConfigs(camera1_saved_config, camera2_saved_config);
|
||||
|
||||
// Camera attached to new port, but strict matching disabled
|
||||
{
|
||||
CameraInfo info1 =
|
||||
new CameraInfo(
|
||||
0, "/dev/video11", "Arducam OV2311 USB Camera", CAM1_OLD_PATHS, 3141, 25446);
|
||||
CameraInfo info2 =
|
||||
new CameraInfo(
|
||||
0, "/dev/video12", "Arducam OV2311 USB Camera", CAM2_NEW_PATH, 3141, 25446);
|
||||
|
||||
var cameraInfos = new ArrayList<CameraInfo>();
|
||||
cameraInfos.add(info1);
|
||||
cameraInfos.add(info2);
|
||||
List<VisionSource> ret1 = inst.tryMatchCamImpl(cameraInfos);
|
||||
|
||||
// and check the new one got matched got matched
|
||||
assertEquals(2, ret1.size());
|
||||
assertEquals(
|
||||
1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info1.path)).count());
|
||||
assertEquals(
|
||||
1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info2.path)).count());
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testInhibitPathChangeIdenticalCams() {
|
||||
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
|
||||
|
||||
var inst = new VisionSourceManager();
|
||||
ConfigManager.getInstance().clearConfig();
|
||||
ConfigManager.getInstance().load();
|
||||
ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = true;
|
||||
|
||||
var CAM2_OLD_PATH =
|
||||
new String[] {"/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"};
|
||||
var CAM2_NEW_PATH =
|
||||
new String[] {"/dev/v4l/by-path/platform-fc880080.usb-usb-0:1:1.3-video-index0"};
|
||||
|
||||
var CAM1_OLD_PATHS =
|
||||
new String[] {
|
||||
"/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
|
||||
"/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0"
|
||||
};
|
||||
|
||||
var camera1_saved_config =
|
||||
new CameraConfiguration(
|
||||
"Arducam OV2311 USB Camera",
|
||||
"Arducam OV2311 USB Camera (1)",
|
||||
"fromt-left",
|
||||
"/dev/video0",
|
||||
CAM1_OLD_PATHS);
|
||||
camera1_saved_config.usbVID = 3141;
|
||||
camera1_saved_config.usbPID = 25446;
|
||||
var camera2_saved_config =
|
||||
new CameraConfiguration(
|
||||
"Arducam OV2311 USB Camera",
|
||||
"Arducam OV2311 USB Camera (1)",
|
||||
"fromt-left",
|
||||
"/dev/video2",
|
||||
CAM2_OLD_PATH);
|
||||
camera2_saved_config.usbVID = 3141;
|
||||
camera2_saved_config.usbPID = 25446;
|
||||
|
||||
// And load our "old" configs
|
||||
inst.registerLoadedConfigs(camera1_saved_config, camera2_saved_config);
|
||||
|
||||
// initial pass with camera in the wrong spot
|
||||
{
|
||||
// Give our cameras new "paths" to fake the windows logic out. this should not
|
||||
// affect strict matching
|
||||
CameraInfo info1 =
|
||||
new CameraInfo(
|
||||
0, "/dev/video11", "Arducam OV2311 USB Camera", CAM1_OLD_PATHS, 3141, 25446);
|
||||
CameraInfo info2 =
|
||||
new CameraInfo(
|
||||
0, "/dev/video12", "Arducam OV2311 USB Camera", CAM2_NEW_PATH, 3141, 25446);
|
||||
|
||||
var cameraInfos = new ArrayList<CameraInfo>();
|
||||
cameraInfos.add(info1);
|
||||
cameraInfos.add(info2);
|
||||
List<VisionSource> ret1 = inst.tryMatchCamImpl(cameraInfos);
|
||||
|
||||
// Our cameras should be "known"
|
||||
assertTrue(inst.knownCameras.contains(info1));
|
||||
assertTrue(inst.knownCameras.contains(info2));
|
||||
assertEquals(2, inst.knownCameras.size());
|
||||
|
||||
// And we should have matched one camera
|
||||
assertEquals(1, ret1.size());
|
||||
// and only matched camera1, not 2
|
||||
assertEquals(
|
||||
1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info1.path)).count());
|
||||
assertEquals(
|
||||
0, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info2.path)).count());
|
||||
}
|
||||
|
||||
// Now move our camera back
|
||||
{
|
||||
CameraInfo info1 =
|
||||
new CameraInfo(
|
||||
0, "/dev/video11", "Arducam OV2311 USB Camera", CAM1_OLD_PATHS, 3141, 25446);
|
||||
CameraInfo info2 =
|
||||
new CameraInfo(
|
||||
0, "/dev/video12", "Arducam OV2311 USB Camera", CAM2_OLD_PATH, 3141, 25446);
|
||||
|
||||
var cameraInfos = new ArrayList<CameraInfo>();
|
||||
cameraInfos.add(info1);
|
||||
cameraInfos.add(info2);
|
||||
List<VisionSource> ret1 = inst.tryMatchCamImpl(cameraInfos);
|
||||
|
||||
// and check the new one got matched got matched
|
||||
assertEquals(1, ret1.size());
|
||||
assertEquals(
|
||||
0, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info1.path)).count());
|
||||
assertEquals(
|
||||
1, ret1.stream().filter(it -> it.cameraConfiguration.path.equals(info2.path)).count());
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testCSICameraMatching() {
|
||||
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
|
||||
|
||||
// List of known cameras
|
||||
var cameraInfos = new ArrayList<CameraInfo>();
|
||||
|
||||
var inst = new VisionSourceManager();
|
||||
ConfigManager.getInstance().clearConfig();
|
||||
ConfigManager.getInstance().load();
|
||||
ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = false;
|
||||
|
||||
CameraInfo info1 =
|
||||
new CameraInfo(
|
||||
-1,
|
||||
"/base/soc/i2c0mux/i2c@0/ov9281@60",
|
||||
"OV9281", // Typically rp1-cfe for unit test changed to CSICAM-DEV
|
||||
new String[] {},
|
||||
-1,
|
||||
-1,
|
||||
CameraType.ZeroCopyPicam);
|
||||
|
||||
CameraInfo info2 =
|
||||
new CameraInfo(
|
||||
-1,
|
||||
"/base/soc/i2c0mux/i2c@1/ov9281@60",
|
||||
"OV9281", // Typically rp1-cfe for unit test changed to CSICAM-DEV
|
||||
new String[] {},
|
||||
-1,
|
||||
-1,
|
||||
CameraType.ZeroCopyPicam);
|
||||
|
||||
var camera1_saved_config =
|
||||
new CameraConfiguration(
|
||||
"OV9281", "OV9281", "test-1", "/base/soc/i2c0mux/i2c@0/ov9281@60", new String[0]);
|
||||
camera1_saved_config.cameraType = CameraType.ZeroCopyPicam;
|
||||
camera1_saved_config.usbVID = -1;
|
||||
camera1_saved_config.usbPID = -1;
|
||||
|
||||
var camera2_saved_config =
|
||||
new CameraConfiguration(
|
||||
"OV9281", "OV9281 (1)", "test-2", "/base/soc/i2c0mux/i2c@1/ov9281@60", new String[0]);
|
||||
camera2_saved_config.usbVID = -1;
|
||||
camera2_saved_config.usbPID = -1;
|
||||
camera2_saved_config.cameraType = CameraType.ZeroCopyPicam;
|
||||
|
||||
cameraInfos.add(info1);
|
||||
cameraInfos.add(info2);
|
||||
|
||||
// Try matching with both cameras being "known"
|
||||
inst.registerLoadedConfigs(camera1_saved_config, camera2_saved_config);
|
||||
var ret1 = inst.tryMatchCamImpl(cameraInfos);
|
||||
|
||||
// Our cameras should be "known"
|
||||
assertTrue(inst.knownCameras.contains(info1));
|
||||
assertTrue(inst.knownCameras.contains(info2));
|
||||
assertEquals(2, inst.knownCameras.size());
|
||||
assertEquals(2, ret1.size());
|
||||
|
||||
// Exactly one camera should have the path we put in
|
||||
for (int i = 0; i < cameraInfos.size(); i++) {
|
||||
var testPath = cameraInfos.get(i).path;
|
||||
assertEquals(
|
||||
1, ret1.stream().filter(it -> testPath.equals(it.cameraConfiguration.path)).count());
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
public void testIdenticalCameras() {
|
||||
Logger.setLevel(LogGroup.Camera, LogLevel.DEBUG);
|
||||
|
||||
// List of known cameras
|
||||
var cameraInfos = new ArrayList<CameraInfo>();
|
||||
|
||||
var inst = new VisionSourceManager();
|
||||
ConfigManager.getInstance().clearConfig();
|
||||
ConfigManager.getInstance().load();
|
||||
ConfigManager.getInstance().getConfig().getNetworkConfig().matchCamerasOnlyByPath = false;
|
||||
|
||||
// Match empty camera infos
|
||||
inst.tryMatchCamImpl(cameraInfos);
|
||||
|
||||
CameraInfo info1 =
|
||||
new CameraInfo(
|
||||
0,
|
||||
"/dev/video0",
|
||||
"Arducam OV2311 USB Camera",
|
||||
new String[] {
|
||||
"/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
|
||||
"/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0"
|
||||
},
|
||||
3141,
|
||||
25446);
|
||||
CameraInfo info2 =
|
||||
new CameraInfo(
|
||||
0,
|
||||
"/dev/video2",
|
||||
"Arducam OV2311 USB Camera",
|
||||
new String[] {
|
||||
"/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
|
||||
"/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"
|
||||
},
|
||||
3141,
|
||||
25446);
|
||||
|
||||
cameraInfos.add(info1);
|
||||
cameraInfos.add(info2);
|
||||
|
||||
// Match two "new" cameras
|
||||
var ret1 = inst.tryMatchCamImpl(cameraInfos);
|
||||
|
||||
// Our cameras should be "known"
|
||||
assertTrue(inst.knownCameras.contains(info1));
|
||||
assertTrue(inst.knownCameras.contains(info2));
|
||||
assertEquals(2, inst.knownCameras.size());
|
||||
assertEquals(2, ret1.size());
|
||||
|
||||
// Exactly one camera should have the path we put in
|
||||
for (int i = 0; i < cameraInfos.size(); i++) {
|
||||
var testPath = cameraInfos.get(i).getUSBPath().get();
|
||||
assertEquals(
|
||||
1,
|
||||
ret1.stream()
|
||||
.filter(it -> testPath.equals(it.cameraConfiguration.getUSBPath().get()))
|
||||
.count());
|
||||
}
|
||||
|
||||
// and the names should be unique
|
||||
for (int i = 0; i < ret1.size(); i++) {
|
||||
var thisName = ret1.get(i).cameraConfiguration.uniqueName;
|
||||
assertEquals(
|
||||
1,
|
||||
ret1.stream().filter(it -> thisName.equals(it.cameraConfiguration.uniqueName)).count());
|
||||
}
|
||||
|
||||
// duplciate cameras, same info, new ref
|
||||
var duplicateCameraInfos = new ArrayList<CameraInfo>();
|
||||
CameraInfo info1_dup =
|
||||
new CameraInfo(
|
||||
0,
|
||||
"/dev/video0",
|
||||
"Arducam OV2311 USB Camera",
|
||||
new String[] {
|
||||
"/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
|
||||
"/dev/v4l/by-path/platform-fc800000.usb-usb-0:1:1.0-video-index0"
|
||||
},
|
||||
3141,
|
||||
25446);
|
||||
CameraInfo info2_dup =
|
||||
new CameraInfo(
|
||||
0,
|
||||
"/dev/video2",
|
||||
"Arducam OV2311 USB Camera",
|
||||
new String[] {
|
||||
"/dev/v4l/by-id/usb-Arducam_Technology_Co.__Ltd._Arducam_OV2311_USB_Camera_UC621-video-index0",
|
||||
"/dev/v4l/by-path/platform-fc880000.usb-usb-0:1:1.0-video-index0"
|
||||
},
|
||||
3141,
|
||||
25446);
|
||||
|
||||
duplicateCameraInfos.add(info1_dup);
|
||||
duplicateCameraInfos.add(info2_dup);
|
||||
|
||||
inst.tryMatchCamImpl(duplicateCameraInfos);
|
||||
|
||||
// Our cameras should be "known", and we should only "know" two cameras still
|
||||
assertTrue(inst.knownCameras.contains(info1_dup));
|
||||
assertTrue(inst.knownCameras.contains(info2_dup));
|
||||
assertEquals(2, inst.knownCameras.size());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -19,7 +19,7 @@ class EstimatedRobotPose:
|
||||
timestampSeconds: float
|
||||
"""The estimated time the frame used to derive the robot pose was taken"""
|
||||
|
||||
targetsUsed: [PhotonTrackedTarget]
|
||||
targetsUsed: list[PhotonTrackedTarget]
|
||||
"""A list of the targets used to compute this pose"""
|
||||
|
||||
strategy: "PoseStrategy"
|
||||
|
||||
@@ -4,7 +4,7 @@ import wpilib
|
||||
|
||||
|
||||
class Packet:
|
||||
def __init__(self, data: list[int]):
|
||||
def __init__(self, data: bytes):
|
||||
"""
|
||||
* Constructs an empty packet.
|
||||
*
|
||||
@@ -30,7 +30,7 @@ class Packet:
|
||||
matches the version of photonlib running in the robot code.
|
||||
"""
|
||||
|
||||
def _getNextByte(self) -> int:
|
||||
def _getNextByteAsInt(self) -> int:
|
||||
retVal = 0x00
|
||||
|
||||
if not self.outOfBytes:
|
||||
@@ -43,7 +43,7 @@ class Packet:
|
||||
|
||||
return retVal
|
||||
|
||||
def getData(self) -> list[int]:
|
||||
def getData(self) -> bytes:
|
||||
"""
|
||||
* Returns the packet data.
|
||||
*
|
||||
@@ -51,7 +51,7 @@ class Packet:
|
||||
"""
|
||||
return self.packetData
|
||||
|
||||
def setData(self, data: list[int]):
|
||||
def setData(self, data: bytes):
|
||||
"""
|
||||
* Sets the packet data.
|
||||
*
|
||||
@@ -65,7 +65,7 @@ class Packet:
|
||||
# Read ints in from the data buffer
|
||||
intList = []
|
||||
for _ in range(numBytes):
|
||||
intList.append(self._getNextByte())
|
||||
intList.append(self._getNextByteAsInt())
|
||||
|
||||
# Interpret the bytes as a floating point number
|
||||
value = struct.unpack(unpackFormat, bytes(intList))[0]
|
||||
|
||||
@@ -4,7 +4,7 @@ from wpilib import Timer
|
||||
import wpilib
|
||||
from photonlibpy.packet import Packet
|
||||
from photonlibpy.photonPipelineResult import PhotonPipelineResult
|
||||
from photonlibpy.version import PHOTONVISION_VERSION, PHOTONLIB_VERSION
|
||||
from photonlibpy.version import PHOTONVISION_VERSION, PHOTONLIB_VERSION # type: ignore[import-untyped]
|
||||
|
||||
|
||||
class VisionLEDMode(Enum):
|
||||
@@ -86,10 +86,11 @@ class PhotonCamera:
|
||||
if len(byteList) < 1:
|
||||
return retVal
|
||||
else:
|
||||
retVal.populateFromPacket(Packet(byteList))
|
||||
pkt = Packet(byteList)
|
||||
retVal.populateFromPacket(pkt)
|
||||
# NT4 allows us to correct the timestamp based on when the message was sent
|
||||
retVal.setTimestampSeconds(
|
||||
timestamp / 1e-6 - retVal.getLatencyMillis() / 1e-3
|
||||
timestamp / 1e6 - retVal.getLatencyMillis() / 1e3
|
||||
)
|
||||
return retVal
|
||||
|
||||
|
||||
@@ -38,3 +38,6 @@ class PhotonPipelineResult:
|
||||
|
||||
def getTargets(self) -> list[PhotonTrackedTarget]:
|
||||
return self.targets
|
||||
|
||||
def hasTargets(self) -> bool:
|
||||
return len(self.targets) > 0
|
||||
|
||||
@@ -75,7 +75,7 @@ class PhotonPoseEstimator:
|
||||
|
||||
self._multiTagFallbackStrategy = PoseStrategy.LOWEST_AMBIGUITY
|
||||
self._reportedErrors: set[int] = set()
|
||||
self._poseCacheTimestampSeconds = -1
|
||||
self._poseCacheTimestampSeconds = -1.0
|
||||
self._lastPose: Optional[Pose3d] = None
|
||||
self._referencePose: Optional[Pose3d] = None
|
||||
|
||||
@@ -143,7 +143,7 @@ class PhotonPoseEstimator:
|
||||
self._multiTagFallbackStrategy = strategy
|
||||
|
||||
@property
|
||||
def referencePose(self) -> Pose3d:
|
||||
def referencePose(self) -> Optional[Pose3d]:
|
||||
"""Return the reference position that is being used by the estimator.
|
||||
|
||||
:returns: the referencePose
|
||||
@@ -163,7 +163,7 @@ class PhotonPoseEstimator:
|
||||
self._referencePose = referencePose
|
||||
|
||||
@property
|
||||
def lastPose(self) -> Pose3d:
|
||||
def lastPose(self) -> Optional[Pose3d]:
|
||||
return self._lastPose
|
||||
|
||||
@lastPose.setter
|
||||
@@ -178,10 +178,10 @@ class PhotonPoseEstimator:
|
||||
self._checkUpdate(self._lastPose, lastPose)
|
||||
self._lastPose = lastPose
|
||||
|
||||
def _invalidatePoseCache(self):
|
||||
self._poseCacheTimestampSeconds = -1
|
||||
def _invalidatePoseCache(self) -> None:
|
||||
self._poseCacheTimestampSeconds = -1.0
|
||||
|
||||
def _checkUpdate(self, oldObj, newObj):
|
||||
def _checkUpdate(self, oldObj, newObj) -> None:
|
||||
if oldObj != newObj and oldObj is not None and oldObj is not newObj:
|
||||
self._invalidatePoseCache()
|
||||
|
||||
@@ -204,27 +204,27 @@ class PhotonPoseEstimator:
|
||||
if not cameraResult:
|
||||
if not self._camera:
|
||||
wpilib.reportError("[PhotonPoseEstimator] Missing camera!", False)
|
||||
return
|
||||
return None
|
||||
cameraResult = self._camera.getLatestResult()
|
||||
|
||||
if cameraResult.timestampSec < 0:
|
||||
return
|
||||
return None
|
||||
|
||||
# If the pose cache timestamp was set, and the result is from the same
|
||||
# timestamp, return an
|
||||
# empty result
|
||||
if (
|
||||
self._poseCacheTimestampSeconds > 0
|
||||
self._poseCacheTimestampSeconds > 0.0
|
||||
and abs(self._poseCacheTimestampSeconds - cameraResult.timestampSec) < 1e-6
|
||||
):
|
||||
return
|
||||
return None
|
||||
|
||||
# Remember the timestamp of the current result used
|
||||
self._poseCacheTimestampSeconds = cameraResult.timestampSec
|
||||
|
||||
# If no targets seen, trivial case -- return empty result
|
||||
if not cameraResult.targets:
|
||||
return
|
||||
return None
|
||||
|
||||
return self._update(cameraResult, self._primaryStrategy)
|
||||
|
||||
@@ -239,7 +239,7 @@ class PhotonPoseEstimator:
|
||||
wpilib.reportError(
|
||||
"[PhotonPoseEstimator] Unknown Position Estimation Strategy!", False
|
||||
)
|
||||
return
|
||||
return None
|
||||
|
||||
if not estimatedPose:
|
||||
self._lastPose = None
|
||||
@@ -280,7 +280,7 @@ class PhotonPoseEstimator:
|
||||
"""
|
||||
lowestAmbiguityTarget = None
|
||||
|
||||
lowestAmbiguityScore = 10
|
||||
lowestAmbiguityScore = 10.0
|
||||
|
||||
for target in result.targets:
|
||||
targetPoseAmbiguity = target.poseAmbiguity
|
||||
@@ -293,7 +293,7 @@ class PhotonPoseEstimator:
|
||||
# Although there are confirmed to be targets, none of them may be fiducial
|
||||
# targets.
|
||||
if not lowestAmbiguityTarget:
|
||||
return
|
||||
return None
|
||||
|
||||
targetFiducialId = lowestAmbiguityTarget.fiducialId
|
||||
|
||||
@@ -301,7 +301,7 @@ class PhotonPoseEstimator:
|
||||
|
||||
if not targetPosition:
|
||||
self._reportFiducialPoseError(targetFiducialId)
|
||||
return
|
||||
return None
|
||||
|
||||
return EstimatedRobotPose(
|
||||
targetPosition.transformBy(
|
||||
|
||||
@@ -408,8 +408,8 @@ public class PhotonPoseEstimator {
|
||||
return Optional.empty();
|
||||
}
|
||||
|
||||
if (estimatedPose.isEmpty()) {
|
||||
lastPose = null;
|
||||
if (estimatedPose.isPresent()) {
|
||||
lastPose = estimatedPose.get().estimatedPose;
|
||||
}
|
||||
|
||||
return estimatedPose;
|
||||
|
||||
@@ -431,7 +431,7 @@ public class PhotonCameraSim implements AutoCloseable {
|
||||
|
||||
detectableTgts.add(
|
||||
new PhotonTrackedTarget(
|
||||
Math.toDegrees(centerRot.getZ()),
|
||||
-Math.toDegrees(centerRot.getZ()),
|
||||
-Math.toDegrees(centerRot.getY()),
|
||||
areaPercent,
|
||||
Math.toDegrees(centerRot.getX()),
|
||||
|
||||
@@ -186,6 +186,9 @@ std::optional<EstimatedRobotPose> PhotonPoseEstimator::Update(
|
||||
ret = std::nullopt;
|
||||
}
|
||||
|
||||
if (ret) {
|
||||
lastPose = ret.value().estimatedPose;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
@@ -260,7 +260,7 @@ class PhotonCameraSim {
|
||||
std::vector<std::pair<double, double>> cornersDouble{cornersFloat.begin(),
|
||||
cornersFloat.end()};
|
||||
detectableTgts.emplace_back(PhotonTrackedTarget{
|
||||
centerRot.Z().convert<units::degrees>().to<double>(),
|
||||
-centerRot.Z().convert<units::degrees>().to<double>(),
|
||||
-centerRot.Y().convert<units::degrees>().to<double>(), areaPercent,
|
||||
centerRot.X().convert<units::degrees>().to<double>(), tgt.fiducialId,
|
||||
pnpSim.best, pnpSim.alt, pnpSim.ambiguity, smallVec, cornersDouble});
|
||||
|
||||
@@ -256,7 +256,8 @@ class VisionSystemSimTest {
|
||||
cameraSim.setMinTargetAreaPixels(0.0);
|
||||
visionSysSim.addVisionTargets(new VisionTargetSim(targetPose, new TargetModel(0.5, 0.5), 3));
|
||||
|
||||
var robotPose = new Pose2d(new Translation2d(10, 0), Rotation2d.fromDegrees(-1.0 * testYaw));
|
||||
// If the robot is rotated x deg (CCW+), the target yaw should be x deg (CW+)
|
||||
var robotPose = new Pose2d(new Translation2d(10, 0), Rotation2d.fromDegrees(testYaw));
|
||||
visionSysSim.update(robotPose);
|
||||
var res = camera.getLatestResult();
|
||||
assertTrue(res.hasTargets());
|
||||
|
||||
@@ -220,8 +220,9 @@ TEST_P(VisionSystemSimTestWithParamsTest, YawAngles) {
|
||||
visionSysSim.AddVisionTargets({photon::VisionTargetSim{
|
||||
targetPose, photon::TargetModel{0.5_m, 0.5_m}, 3}});
|
||||
|
||||
robotPose = frc::Pose2d{frc::Translation2d{10_m, 0_m},
|
||||
frc::Rotation2d{-1 * GetParam()}};
|
||||
// If the robot is rotated x deg (CCW+), the target yaw should be x deg (CW+)
|
||||
robotPose =
|
||||
frc::Pose2d{frc::Translation2d{10_m, 0_m}, frc::Rotation2d{GetParam()}};
|
||||
visionSysSim.Update(robotPose);
|
||||
ASSERT_TRUE(camera.GetLatestResult().HasTargets());
|
||||
ASSERT_NEAR(GetParam().to<double>(),
|
||||
|
||||
@@ -35,6 +35,7 @@ import org.photonvision.common.hardware.Platform;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.LogLevel;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.common.logging.PvCSCoreLogger;
|
||||
import org.photonvision.common.networking.NetworkManager;
|
||||
import org.photonvision.common.util.TestUtils;
|
||||
import org.photonvision.common.util.numbers.IntegerCouple;
|
||||
@@ -65,6 +66,7 @@ public class Main {
|
||||
private static final boolean isRelease = PhotonVersion.isRelease;
|
||||
|
||||
private static boolean isTestMode = false;
|
||||
private static boolean isSmoketest = false;
|
||||
private static Path testModeFolder = null;
|
||||
private static boolean printDebugLogs;
|
||||
|
||||
@@ -90,6 +92,11 @@ public class Main {
|
||||
"clear-config",
|
||||
false,
|
||||
"Clears PhotonVision pipeline and networking settings. Preserves log files");
|
||||
options.addOption(
|
||||
"s",
|
||||
"smoketest",
|
||||
false,
|
||||
"Exit Photon after loading native libraries and camera configs, but before starting up camera runners");
|
||||
|
||||
CommandLineParser parser = new DefaultParser();
|
||||
CommandLine cmd = parser.parse(options, args);
|
||||
@@ -127,6 +134,10 @@ public class Main {
|
||||
if (cmd.hasOption("clear-config")) {
|
||||
ConfigManager.getInstance().clearConfig();
|
||||
}
|
||||
|
||||
if (cmd.hasOption("smoketest")) {
|
||||
isSmoketest = true;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
@@ -266,7 +277,7 @@ public class Main {
|
||||
|
||||
CameraConfiguration camConf2024 =
|
||||
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2024");
|
||||
if (camConf2024 == null || true) {
|
||||
if (camConf2024 == null) {
|
||||
camConf2024 =
|
||||
new CameraConfiguration(
|
||||
"WPI2024",
|
||||
@@ -337,11 +348,17 @@ public class Main {
|
||||
|
||||
public static void main(String[] args) {
|
||||
try {
|
||||
TestUtils.loadLibraries();
|
||||
logger.info("Native libraries loaded.");
|
||||
boolean success = TestUtils.loadLibraries();
|
||||
|
||||
if (!success) {
|
||||
logger.error("Failed to load native libraries! Giving up :(");
|
||||
System.exit(1);
|
||||
}
|
||||
} catch (Exception e) {
|
||||
logger.error("Failed to load native libraries!", e);
|
||||
System.exit(1);
|
||||
}
|
||||
logger.info("Native libraries loaded.");
|
||||
|
||||
try {
|
||||
if (Platform.isRaspberryPi()) {
|
||||
@@ -393,6 +410,8 @@ public class Main {
|
||||
+ Platform.getPlatformName()
|
||||
+ (Platform.isRaspberryPi() ? (" (Pi " + PiVersion.getPiVersion() + ")") : ""));
|
||||
|
||||
PvCSCoreLogger.getInstance();
|
||||
|
||||
logger.debug("Loading ConfigManager...");
|
||||
ConfigManager.getInstance().load(); // init config manager
|
||||
ConfigManager.getInstance().requestSave();
|
||||
@@ -412,6 +431,11 @@ public class Main {
|
||||
NeuralNetworkModelManager.getInstance()
|
||||
.initialize(ConfigManager.getInstance().getModelsDirectory());
|
||||
|
||||
if (isSmoketest) {
|
||||
logger.info("PhotonVision base functionality loaded -- smoketest complete");
|
||||
System.exit(0);
|
||||
}
|
||||
|
||||
if (!isTestMode) {
|
||||
logger.debug("Loading VisionSourceManager...");
|
||||
VisionSourceManager.getInstance()
|
||||
|
||||
@@ -131,18 +131,16 @@ public class DataSocketHandler {
|
||||
case SMT_DRIVERMODE:
|
||||
{
|
||||
// TODO: what is this event?
|
||||
var data = (HashMap<String, Object>) entryValue;
|
||||
var dmExpEvent =
|
||||
new IncomingWebSocketEvent<Integer>(
|
||||
DataChangeDestination.DCD_ACTIVEMODULE, "driverExposure", data);
|
||||
var dmBrightEvent =
|
||||
new IncomingWebSocketEvent<Integer>(
|
||||
DataChangeDestination.DCD_ACTIVEMODULE, "driverBrightness", data);
|
||||
var data = (Boolean) entryValue;
|
||||
var dmIsDriverEvent =
|
||||
new IncomingWebSocketEvent<Boolean>(
|
||||
DataChangeDestination.DCD_ACTIVEMODULE, "isDriver", data);
|
||||
DataChangeDestination.DCD_ACTIVEMODULE,
|
||||
"isDriverMode",
|
||||
data,
|
||||
cameraIndex,
|
||||
context);
|
||||
|
||||
dcService.publishEvents(dmExpEvent, dmBrightEvent, dmIsDriverEvent);
|
||||
dcService.publishEvents(dmIsDriverEvent);
|
||||
break;
|
||||
}
|
||||
case SMT_CHANGECAMERANAME:
|
||||
@@ -350,8 +348,7 @@ public class DataSocketHandler {
|
||||
}
|
||||
}
|
||||
|
||||
private void sendMessage(Object message, WsContext user) throws JsonProcessingException {
|
||||
ByteBuffer b = ByteBuffer.wrap(objectMapper.writeValueAsBytes(message));
|
||||
private void sendMessage(ByteBuffer b, WsContext user) throws JsonProcessingException {
|
||||
if (user.session.isOpen()) {
|
||||
user.send(b);
|
||||
}
|
||||
@@ -359,16 +356,18 @@ public class DataSocketHandler {
|
||||
|
||||
public void broadcastMessage(Object message, WsContext userToSkip)
|
||||
throws JsonProcessingException {
|
||||
ByteBuffer b = ByteBuffer.wrap(objectMapper.writeValueAsBytes(message));
|
||||
|
||||
if (userToSkip == null) {
|
||||
for (WsContext user : users) {
|
||||
sendMessage(message, user);
|
||||
sendMessage(b, user);
|
||||
}
|
||||
} else {
|
||||
var skipUserPort = ((InetSocketAddress) userToSkip.session.getRemoteAddress()).getPort();
|
||||
for (WsContext user : users) {
|
||||
var userPort = ((InetSocketAddress) user.session.getRemoteAddress()).getPort();
|
||||
if (userPort != skipUserPort) {
|
||||
sendMessage(message, user);
|
||||
sendMessage(b, user);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -31,6 +31,9 @@ import java.util.HashMap;
|
||||
import java.util.Optional;
|
||||
import javax.imageio.ImageIO;
|
||||
import org.apache.commons.io.FileUtils;
|
||||
import org.opencv.core.MatOfByte;
|
||||
import org.opencv.core.MatOfInt;
|
||||
import org.opencv.imgcodecs.Imgcodecs;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
import org.photonvision.common.configuration.NetworkConfig;
|
||||
import org.photonvision.common.dataflow.DataChangeDestination;
|
||||
@@ -580,6 +583,77 @@ public class RequestHandler {
|
||||
ctx.status(204);
|
||||
}
|
||||
|
||||
public static void onCalibrationSnapshotRequest(Context ctx) {
|
||||
logger.info(ctx.queryString().toString());
|
||||
|
||||
int idx = Integer.parseInt(ctx.queryParam("cameraIdx"));
|
||||
var width = Integer.parseInt(ctx.queryParam("width"));
|
||||
var height = Integer.parseInt(ctx.queryParam("height"));
|
||||
var observationIdx = Integer.parseInt(ctx.queryParam("snapshotIdx"));
|
||||
|
||||
CameraCalibrationCoefficients calList =
|
||||
VisionModuleManager.getInstance()
|
||||
.getModule(idx)
|
||||
.getStateAsCameraConfig()
|
||||
.calibrations
|
||||
.stream()
|
||||
.filter(
|
||||
it ->
|
||||
Math.abs(it.resolution.width - width) < 1e-4
|
||||
&& Math.abs(it.resolution.height - height) < 1e-4)
|
||||
.findFirst()
|
||||
.orElse(null);
|
||||
|
||||
if (calList == null || calList.observations.size() < observationIdx) {
|
||||
ctx.status(404);
|
||||
return;
|
||||
}
|
||||
|
||||
// encode as jpeg to save even more space. reduces size of a 1280p image from 300k to 25k
|
||||
var jpegBytes = new MatOfByte();
|
||||
Imgcodecs.imencode(
|
||||
".jpg",
|
||||
calList.observations.get(observationIdx).snapshotData.getAsMat(),
|
||||
jpegBytes,
|
||||
new MatOfInt(Imgcodecs.IMWRITE_JPEG_QUALITY, 60));
|
||||
|
||||
ctx.result(jpegBytes.toArray());
|
||||
jpegBytes.release();
|
||||
|
||||
ctx.status(200);
|
||||
}
|
||||
|
||||
public static void onCalibrationExportRequest(Context ctx) {
|
||||
logger.info(ctx.queryString().toString());
|
||||
|
||||
int idx = Integer.parseInt(ctx.queryParam("cameraIdx"));
|
||||
var width = Integer.parseInt(ctx.queryParam("width"));
|
||||
var height = Integer.parseInt(ctx.queryParam("height"));
|
||||
|
||||
var cc = VisionModuleManager.getInstance().getModule(idx).getStateAsCameraConfig();
|
||||
|
||||
CameraCalibrationCoefficients calList =
|
||||
cc.calibrations.stream()
|
||||
.filter(
|
||||
it ->
|
||||
Math.abs(it.resolution.width - width) < 1e-4
|
||||
&& Math.abs(it.resolution.height - height) < 1e-4)
|
||||
.findFirst()
|
||||
.orElse(null);
|
||||
|
||||
if (calList == null) {
|
||||
ctx.status(404);
|
||||
return;
|
||||
}
|
||||
|
||||
var filename = "photon_calibration_" + cc.uniqueName + "_" + width + "x" + height + ".json";
|
||||
ctx.contentType("application/zip");
|
||||
ctx.header("Content-Disposition", "attachment; filename=\"" + filename + "\"");
|
||||
ctx.json(calList);
|
||||
|
||||
ctx.status(200);
|
||||
}
|
||||
|
||||
public static void onImageSnapshotsRequest(Context ctx) {
|
||||
var snapshots = new ArrayList<HashMap<String, Object>>();
|
||||
var cameraDirs = ConfigManager.getInstance().getImageSavePath().toFile().listFiles();
|
||||
|
||||
@@ -130,6 +130,8 @@ public class Server {
|
||||
app.post("/api/utils/restartDevice", RequestHandler::onDeviceRestartRequest);
|
||||
app.post("/api/utils/publishMetrics", RequestHandler::onMetricsPublishRequest);
|
||||
app.get("/api/utils/getImageSnapshots", RequestHandler::onImageSnapshotsRequest);
|
||||
app.get("/api/utils/getCalSnapshot", RequestHandler::onCalibrationSnapshotRequest);
|
||||
app.get("/api/utils/getCalibrationJSON", RequestHandler::onCalibrationExportRequest);
|
||||
|
||||
// Calibration
|
||||
app.post("/api/calibration/end", RequestHandler::onCalibrationEndRequest);
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
plugins {
|
||||
id "cpp"
|
||||
id "google-test-test-suite"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
|
||||
id "com.dorongold.task-tree" version "2.1.0"
|
||||
}
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
plugins {
|
||||
id "cpp"
|
||||
id "google-test-test-suite"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
|
||||
id "com.dorongold.task-tree" version "2.1.0"
|
||||
}
|
||||
|
||||
@@ -39,8 +39,8 @@ class Robot : public frc::TimedRobot {
|
||||
void TeleopPeriodic() override;
|
||||
|
||||
private:
|
||||
// Change this to match the name of your camera
|
||||
photon::PhotonCamera camera{"photonvision"};
|
||||
// Change this to match the name of your camera as shown in the web UI
|
||||
photon::PhotonCamera camera{"YOUR_CAMERA_NAME_HERE"};
|
||||
// PID constants should be tuned per robot
|
||||
frc::PIDController controller{.1, 0, 0};
|
||||
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
plugins {
|
||||
id "cpp"
|
||||
id "google-test-test-suite"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
|
||||
id "com.dorongold.task-tree" version "2.1.0"
|
||||
}
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
plugins {
|
||||
id "cpp"
|
||||
id "google-test-test-suite"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
|
||||
id "com.dorongold.task-tree" version "2.1.0"
|
||||
}
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
plugins {
|
||||
id "cpp"
|
||||
id "google-test-test-suite"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
|
||||
id "com.dorongold.task-tree" version "2.1.0"
|
||||
}
|
||||
@@ -12,8 +12,8 @@ repositories {
|
||||
}
|
||||
|
||||
wpi.maven.useDevelopment = true
|
||||
wpi.versions.wpilibVersion = "2024.2.1"
|
||||
wpi.versions.wpimathVersion = "2024.2.1"
|
||||
wpi.versions.wpilibVersion = "2024.3.2"
|
||||
wpi.versions.wpimathVersion = "2024.3.2"
|
||||
|
||||
apply from: "${rootDir}/../shared/examples_common.gradle"
|
||||
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
plugins {
|
||||
id "java"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
}
|
||||
|
||||
sourceCompatibility = JavaVersion.VERSION_11
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
plugins {
|
||||
id "java"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
}
|
||||
|
||||
sourceCompatibility = JavaVersion.VERSION_11
|
||||
|
||||
@@ -48,8 +48,8 @@ public class Robot extends TimedRobot {
|
||||
// How far from the target we want to be
|
||||
final double GOAL_RANGE_METERS = Units.feetToMeters(3);
|
||||
|
||||
// Change this to match the name of your camera
|
||||
PhotonCamera camera = new PhotonCamera("photonvision");
|
||||
// Change this to match the name of your camera as shown in the web UI
|
||||
PhotonCamera camera = new PhotonCamera("YOUR_CAMERA_NAME_HERE");
|
||||
|
||||
// PID constants should be tuned per robot
|
||||
final double LINEAR_P = 0.1;
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
plugins {
|
||||
id "java"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
}
|
||||
|
||||
sourceCompatibility = JavaVersion.VERSION_11
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
plugins {
|
||||
id "java"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
}
|
||||
|
||||
sourceCompatibility = JavaVersion.VERSION_11
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
plugins {
|
||||
id "java"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.2.1"
|
||||
id "edu.wpi.first.GradleRIO" version "2024.3.2"
|
||||
}
|
||||
|
||||
sourceCompatibility = JavaVersion.VERSION_11
|
||||
@@ -11,8 +11,8 @@ apply from: "${rootDir}/../shared/examples_common.gradle"
|
||||
def ROBOT_MAIN_CLASS = "frc.robot.Main"
|
||||
|
||||
wpi.maven.useDevelopment = true
|
||||
wpi.versions.wpilibVersion = "2024.2.1"
|
||||
wpi.versions.wpimathVersion = "2024.2.1"
|
||||
wpi.versions.wpilibVersion = "2024.3.2"
|
||||
wpi.versions.wpimathVersion = "2024.3.2"
|
||||
|
||||
|
||||
// Define my targets (RoboRIO) and artifacts (deployable files)
|
||||
|
||||
@@ -80,6 +80,9 @@ if [[ "$DISTRO" = "Ubuntu" && "$INSTALL_NETWORK_MANAGER" != "true" && -z "$QUIET
|
||||
fi
|
||||
fi
|
||||
|
||||
echo "Update package list"
|
||||
apt-get update
|
||||
|
||||
echo "Installing curl..."
|
||||
apt-get install --yes curl
|
||||
echo "curl installation complete."
|
||||
@@ -132,6 +135,13 @@ fi
|
||||
echo "Installing additional math packages"
|
||||
apt-get install --yes libcholmod3 liblapack3 libsuitesparseconfig5
|
||||
|
||||
echo "Installing v4l-utils..."
|
||||
apt-get install --yes v4l-utils
|
||||
echo "v4l-utils installation complete."
|
||||
|
||||
echo "Installing sqlite3"
|
||||
apt-get install --yes sqlite3
|
||||
|
||||
echo "Downloading latest stable release of PhotonVision..."
|
||||
mkdir -p /opt/photonvision
|
||||
cd /opt/photonvision
|
||||
|
||||
Reference in New Issue
Block a user