From 7ff630dc442a82e86044ebfadeb0b665a4f10f89 Mon Sep 17 00:00:00 2001 From: Matt Date: Wed, 28 Dec 2022 11:21:41 -0800 Subject: [PATCH] Replace MMAL driver with Libcamera (#491) Co-authored-by: Chris Gerth --- .github/workflows/main.yml | 2 +- build.gradle | 3 +- photon-client/package-lock.json | 25 +- photon-client/src/views/CamerasView.vue | 20 ++ photon-client/src/views/PipelineView.vue | 6 +- .../configuration/CameraConfiguration.java | 38 ++- .../configuration/PhotonConfiguration.java | 6 +- .../common/hardware/PiVersion.java | 2 +- .../photonvision/common/util/TestUtils.java | 1 + .../org/photonvision/raspi/LibCameraJNI.java | 191 ++++++++++++++ .../java/org/photonvision/raspi/PicamJNI.java | 163 ------------ .../vision/camera/LibcameraGpuSettables.java | 220 ++++++++++++++++ .../vision/camera/LibcameraGpuSource.java | 87 +++++++ .../vision/camera/ZeroCopyPicamSource.java | 234 ------------------ .../org/photonvision/vision/frame/Frame.java | 54 ++-- .../vision/frame/FrameProvider.java | 14 ++ ...eProvider.java => FrameThresholdType.java} | 22 +- .../frame/consumer/FileSaveFrameConsumer.java | 10 +- .../frame/consumer/MJPGFrameConsumer.java | 8 +- .../AcceleratedPicamFrameProvider.java | 60 ----- .../frame/provider/CpuImageProcessor.java | 124 ++++++++++ .../frame/provider/FileFrameProvider.java | 16 +- .../provider/LibcameraGpuFrameProvider.java | 114 +++++++++ .../frame/provider/USBFrameProvider.java | 13 +- .../pipe/impl/AprilTagDetectionPipe.java | 12 +- .../vision/pipe/impl/FilterContoursPipe.java | 4 +- .../vision/pipeline/AprilTagPipeline.java | 56 ++--- .../vision/pipeline/CVPipeline.java | 20 +- .../vision/pipeline/CVPipelineSettings.java | 6 - .../vision/pipeline/Calibrate3dPipeline.java | 31 +-- .../Calibration3dPipelineSettings.java | 7 + .../vision/pipeline/ColoredShapePipeline.java | 78 +----- .../vision/pipeline/DriverModePipeline.java | 34 +-- .../vision/pipeline/OutputStreamPipeline.java | 17 +- .../vision/pipeline/ReflectivePipeline.java | 96 +++---- .../pipeline/result/CVPipelineResult.java | 21 +- .../vision/processes/VisionModule.java | 82 +++--- .../vision/processes/VisionRunner.java | 27 +- .../vision/processes/VisionSourceManager.java | 43 ++-- .../vision/videoStream/SocketVideoStream.java | 12 +- .../AcceleratedPicamFrameProviderTest.java | 52 ---- .../frame/provider/FileFrameProviderTest.java | 12 +- .../vision/frame/provider/LibcameraTest.java | 38 +++ .../vision/pipeline/AprilTagTest.java | 9 +- .../vision/pipeline/Calibrate3dPipeTest.java | 12 +- .../vision/pipeline/CirclePNPTest.java | 4 +- .../pipeline/ColoredShapePipelineTest.java | 12 +- .../pipeline/ReflectivePipelineTest.java | 16 +- .../vision/pipeline/SolvePNPTest.java | 30 ++- .../src/main/java/org/photonvision/Main.java | 11 +- .../nativelibraries/libphotonlibcamera.so | Bin 0 -> 141936 bytes scripts/generatePiImage.sh | 18 +- scripts/install.sh | 2 +- 53 files changed, 1261 insertions(+), 934 deletions(-) create mode 100644 photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java delete mode 100644 photon-core/src/main/java/org/photonvision/raspi/PicamJNI.java create mode 100644 photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java create mode 100644 photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSource.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/camera/ZeroCopyPicamSource.java rename photon-core/src/main/java/org/photonvision/vision/frame/{provider/NetworkFrameProvider.java => FrameThresholdType.java} (58%) delete mode 100644 photon-core/src/main/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProvider.java create mode 100644 photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java create mode 100644 photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java delete mode 100644 photon-core/src/test/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProviderTest.java create mode 100644 photon-core/src/test/java/org/photonvision/vision/frame/provider/LibcameraTest.java create mode 100755 photon-server/src/main/resources/nativelibraries/libphotonlibcamera.so diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml index 04df6cdcf..2af036bb8 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/main.yml @@ -375,7 +375,7 @@ jobs: ./gradlew photon-server:shadowJar --max-workers 2 if: ${{ (matrix.arch-override == 'none') }} - # The image will only pull the Pi JAR in + # The image will only pull the Pi32 JAR in - name: Generate image if: ${{ github.event_name != 'pull_request' && (matrix.artifact-name) == 'LinuxArm32' }} run: | diff --git a/build.gradle b/build.gradle index a95bfc2de..fe388df47 100644 --- a/build.gradle +++ b/build.gradle @@ -36,9 +36,10 @@ ext { jniPlatforms = ['linuxarm32'] } else if(project.hasProperty('winonly')) { jniPlatforms = ['windowsx86-64'] + } else if(project.hasProperty('aarch64only')) { + jniPlatforms = ['linuxaarch64bionic'] } else { jniPlatforms = ['linuxarm64', 'linuxarm32', 'linuxx86-64', 'osxuniversal', 'windowsx86-64'] - } println("Building for archs " + jniPlatforms) diff --git a/photon-client/package-lock.json b/photon-client/package-lock.json index b3b6a219c..1f579daa8 100644 --- a/photon-client/package-lock.json +++ b/photon-client/package-lock.json @@ -5,7 +5,6 @@ "requires": true, "packages": { "": { - "name": "photon-client", "version": "3.0.0", "dependencies": { "@femessage/log-viewer": "^1.4.2", @@ -19,7 +18,8 @@ "three-full": "^28.0.2", "vue": "^2.6.12", "vue-axios": "^2.1.5", - "vue-native-websocket": "git+https://github.com/PhotonVision/vue-native-websocket.git#5189f29", "vue-router": "^3.4.3", + "vue-native-websocket": "git+https://git@github.com/PhotonVision/vue-native-websocket.git#5189f29", + "vue-router": "^3.4.3", "vuetify": "^2.3.10", "vuex": "^3.5.1" }, @@ -2682,6 +2682,7 @@ "thread-loader": "^2.1.3", "url-loader": "^2.2.0", "vue-loader": "^15.9.2", + "vue-loader-v16": "npm:vue-loader@^16.0.0-beta.3", "vue-style-loader": "^4.1.2", "webpack": "^4.0.0", "webpack-bundle-analyzer": "^3.8.0", @@ -3115,6 +3116,7 @@ "merge-source-map": "^1.1.0", "postcss": "^7.0.14", "postcss-selector-parser": "^6.0.2", + "prettier": "^1.18.2", "source-map": "~0.6.1", "vue-template-es2015-compiler": "^1.9.0" }, @@ -4701,6 +4703,7 @@ "dependencies": { "anymatch": "~3.1.1", "braces": "~3.0.2", + "fsevents": "~2.1.2", "glob-parent": "~5.1.0", "is-binary-path": "~2.1.0", "is-glob": "~4.0.1", @@ -9164,6 +9167,9 @@ "version": "4.0.0", "dev": true, "license": "MIT", + "dependencies": { + "graceful-fs": "^4.1.6" + }, "optionalDependencies": { "graceful-fs": "^4.1.6" } @@ -9175,7 +9181,11 @@ "@babel/runtime": "^7.14.0", "atob": "^2.1.2", "btoa": "^1.2.1", - "fflate": "^0.4.8" + "canvg": "^3.0.6", + "core-js": "^3.6.0", + "dompurify": "^2.2.0", + "fflate": "^0.4.8", + "html2canvas": "^1.0.0-rc.5" }, "optionalDependencies": { "canvg": "^3.0.6", @@ -14190,8 +14200,10 @@ "dev": true, "license": "MIT", "dependencies": { + "chokidar": "^3.4.0", "graceful-fs": "^4.1.2", - "neo-async": "^2.5.0" + "neo-async": "^2.5.0", + "watchpack-chokidar2": "^2.0.0" }, "optionalDependencies": { "chokidar": "^3.4.0", @@ -14300,6 +14312,7 @@ "anymatch": "^2.0.0", "async-each": "^1.0.1", "braces": "^2.3.2", + "fsevents": "^1.2.7", "glob-parent": "^3.1.0", "inherits": "^2.0.3", "is-binary-path": "^1.0.0", @@ -14540,6 +14553,7 @@ "anymatch": "^2.0.0", "async-each": "^1.0.1", "braces": "^2.3.2", + "fsevents": "^1.2.7", "glob-parent": "^3.1.0", "inherits": "^2.0.3", "is-binary-path": "^1.0.0", @@ -25270,7 +25284,8 @@ }, "vue-native-websocket": { "version": "git+ssh://git@github.com/PhotonVision/vue-native-websocket.git#7a327918e03b215b6899b0d648c5130ece1fa912", - "from": "vue-native-websocket@git+https://github.com/PhotonVision/vue-native-websocket.git#7a32791" }, + "from": "vue-native-websocket@git+https://git@github.com/PhotonVision/vue-native-websocket.git#5189f29" + }, "vue-router": { "version": "3.4.3" }, diff --git a/photon-client/src/views/CamerasView.vue b/photon-client/src/views/CamerasView.vue index 888b81102..27ad3044e 100644 --- a/photon-client/src/views/CamerasView.vue +++ b/photon-client/src/views/CamerasView.vue @@ -218,6 +218,17 @@ tooltip="Enables or Disables camera automatic adjustment for current lighting conditions" @input="e => handlePipelineUpdate('cameraAutoExposure', e)" /> + Processing @ {{ Math.round($store.state.pipelineResults.fps) }} FPS – - {{ Math.min(Math.round($store.state.pipelineResults.latency), 9999) }} ms latency - HSV thresholds are too broad; narrow them for better performance - stop viewing the raw stream for better performance + HSV thresholds are too broad; narrow them for better performance + stop viewing the raw stream for better performance + {{ Math.min(Math.round($store.state.pipelineResults.latency), 9999) }} ms latency calibrations; @@ -59,15 +62,17 @@ public class CameraConfiguration { public DriverModePipelineSettings driveModeSettings = new DriverModePipelineSettings(); public CameraConfiguration(String baseName, String path) { - this(baseName, baseName, baseName, path); + this(baseName, baseName, baseName, path, new String[0]); } - public CameraConfiguration(String baseName, String uniqueName, String nickname, String path) { + public CameraConfiguration( + String baseName, String uniqueName, String nickname, String path, String[] alternates) { this.baseName = baseName; this.uniqueName = uniqueName; this.nickname = nickname; this.path = path; this.calibrations = new ArrayList<>(); + this.otherPaths = alternates; logger.debug( "Creating USB camera configuration for " @@ -145,4 +150,33 @@ public class CameraConfiguration { .ifPresent(calibrations::remove); calibrations.add(calibration); } + + @Override + public String toString() { + return "CameraConfiguration [baseName=" + + baseName + + ", uniqueName=" + + uniqueName + + ", nickname=" + + nickname + + ", path=" + + path + + ", otherPaths=" + + Arrays.toString(otherPaths) + + ", cameraType=" + + cameraType + + ", FOV=" + + FOV + + ", calibrations=" + + calibrations + + ", currentPipelineIndex=" + + currentPipelineIndex + + ", streamIndex=" + + streamIndex + + ", pipelineSettings=" + + pipelineSettings + + ", driveModeSettings=" + + driveModeSettings + + "]"; + } } diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java b/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java index 4230387a9..ba3e75181 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java @@ -25,7 +25,7 @@ import java.util.stream.Collectors; import org.photonvision.PhotonVersion; import org.photonvision.common.hardware.Platform; import org.photonvision.common.util.SerializationUtils; -import org.photonvision.raspi.PicamJNI; +import org.photonvision.raspi.LibCameraJNI; import org.photonvision.vision.processes.VisionModule; import org.photonvision.vision.processes.VisionModuleManager; import org.photonvision.vision.processes.VisionSource; @@ -110,8 +110,8 @@ public class PhotonConfiguration { generalSubmap.put("version", PhotonVersion.versionString); generalSubmap.put( "gpuAcceleration", - PicamJNI.isSupported() - ? "Zerocopy MMAL on " + PicamJNI.getSensorModel().getFriendlyName() + LibCameraJNI.isSupported() + ? "Zerocopy Libcamera on " + LibCameraJNI.getSensorModel().getFriendlyName() : ""); // TODO add support for other types of GPU accel generalSubmap.put("hardwareModel", hardwareConfig.deviceName); generalSubmap.put("hardwarePlatform", Platform.getPlatformName()); diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java b/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java index dbf23ac7e..f0817f70c 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java @@ -34,7 +34,7 @@ public enum PiVersion { private static final ShellExec shell = new ShellExec(true, false); private static final PiVersion currentPiVersion = calcPiVersion(); - PiVersion(String s) { + private PiVersion(String s) { this.identifier = s.toLowerCase(); } diff --git a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java index 3bb6296c9..2a50ea5ea 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java @@ -330,6 +330,7 @@ public class TestUtils { private static int DefaultTimeoutMillis = 5000; public static void showImage(Mat frame, String title, int timeoutMs) { + if (frame.empty()) return; try { HighGui.imshow(title, frame); HighGui.waitKey(timeoutMs); diff --git a/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java new file mode 100644 index 000000000..4ebc2c873 --- /dev/null +++ b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java @@ -0,0 +1,191 @@ +/* + * 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 . + */ + +package org.photonvision.raspi; + +import java.io.File; +import java.io.IOException; +import java.io.InputStream; +import java.net.URL; +import java.nio.file.Files; +import java.nio.file.Path; +import org.photonvision.common.logging.LogGroup; +import org.photonvision.common.logging.Logger; + +public class LibCameraJNI { + private static boolean libraryLoaded = false; + private static Logger logger = new Logger(LibCameraJNI.class, LogGroup.Camera); + + public static final Object CAMERA_LOCK = new Object(); + + public static synchronized void forceLoad() throws IOException { + if (libraryLoaded) return; + + try { + File libDirectory = Path.of("lib/").toFile(); + if (!libDirectory.exists()) { + Files.createDirectory(libDirectory.toPath()).toFile(); + } + + // We always extract the shared object (we could hash each so, but that's a lot of work) + URL resourceURL = LibCameraJNI.class.getResource("/nativelibraries/libphotonlibcamera.so"); + File libFile = Path.of("lib/libphotonlibcamera.so").toFile(); + try (InputStream in = resourceURL.openStream()) { + if (libFile.exists()) Files.delete(libFile.toPath()); + Files.copy(in, libFile.toPath()); + } catch (Exception e) { + logger.error("Could not extract the native library!"); + } + System.load(libFile.getAbsolutePath()); + + libraryLoaded = true; + logger.info("Successfully loaded libpicam shared object"); + } catch (UnsatisfiedLinkError e) { + logger.error("Couldn't load libpicam shared object"); + e.printStackTrace(); + } + } + + public enum SensorModel { + Disconnected, + OV5647, // Picam v1 + IMX219, // Picam v2 + IMX477, // Picam HQ + OV9281, + OV7251, + Unknown; + + public String getFriendlyName() { + switch (this) { + case Disconnected: + return "Disconnected Camera"; + case OV5647: + return "Camera Module v1"; + case IMX219: + return "Camera Module v2"; + case IMX477: + return "HQ Camera"; + case OV9281: + return "OV9281"; + case OV7251: + return "OV7251"; + case Unknown: + default: + return "Unknown Camera"; + } + } + } + + public static SensorModel getSensorModel() { + int model = getSensorModelRaw(); + return SensorModel.values()[model]; + } + + public static boolean isSupported() { + return libraryLoaded + // && getSensorModel() != PicamJNI.SensorModel.Disconnected + // && Platform.isRaspberryPi() + && isLibraryWorking(); + } + + private static native boolean isLibraryWorking(); + + public static native int getSensorModelRaw(); + + // ======================================================== // + + /** + * Creates a new runner with a given width/height/fps + * + * @param width Camera video mode width in pixels + * @param height Camera video mode height in pixels + * @param fps Camera video mode FPS + * @return success of creating a camera object + */ + public static native boolean createCamera(int width, int height, int rotation); + + /** + * Starts the camera thresholder and display threads running. Make sure that this function is + * called syncronously with stopCamera and returnFrame! + */ + public static native boolean startCamera(); + + /** Stops the camera runner. Make sure to call prior to destroying the camera! */ + public static native boolean stopCamera(); + + // Destroy all native resources associated with a camera. Ensure stop is called prior! + public static native boolean destroyCamera(); + + // ======================================================== // + + // Set thresholds on [0..1] + public static native boolean setThresholds( + double hl, double sl, double vl, double hu, double su, double vu, boolean hueInverted); + + public static native boolean setAutoExposure(boolean doAutoExposure); + + // Exposure time, in microseconds + public static native boolean setExposure(int exposureUs); + + // Set brighness on [-1, 1] + public static native boolean setBrightness(double brightness); + + // Unknown ranges for red and blue AWB gain + public static native boolean setAwbGain(double red, double blue); + + /** + * Get the time when the first pixel exposure was started, in the same timebase as libcamera gives + * the frame capture time. Units are nanoseconds. + */ + public static native long getFrameCaptureTime(); + + /** + * Get the current time, in the same timebase as libcamera gives the frame capture time. Units are + * nanoseconds. + */ + public static native long getLibcameraTimestamp(); + + public static native long setFramesToCopy(boolean copyIn, boolean copyOut); + + // Analog gain multiplier to apply to all color channels, on [1, Big Number] + public static native boolean setAnalogGain(double analog); + + /** Block until a new frame is avaliable from native code. */ + public static native boolean awaitNewFrame(); + + /** + * Get a pointer to the most recent color mat generated. Call this immediatly after awaitNewFrame, + * and call onlly once per new frame! + */ + public static native long takeColorFrame(); + + /** + * Get a pointer to the most recent processed mat generated. Call this immediatly after + * awaitNewFrame, and call onlly once per new frame! + */ + public static native long takeProcessedFrame(); + + /** + * Set the GPU processing type we should do. Enum of [none, HSV, greyscale, adaptive threshold]. + */ + public static native boolean setGpuProcessType(int type); + + public static native int getGpuProcessType(); + + // /** Release a frame pointer back to the libcamera driver code to be filled again */ + // public static native long returnFrame(long frame); +} diff --git a/photon-core/src/main/java/org/photonvision/raspi/PicamJNI.java b/photon-core/src/main/java/org/photonvision/raspi/PicamJNI.java deleted file mode 100644 index b987d419b..000000000 --- a/photon-core/src/main/java/org/photonvision/raspi/PicamJNI.java +++ /dev/null @@ -1,163 +0,0 @@ -/* - * 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 . - */ - -package org.photonvision.raspi; - -import java.io.File; -import java.io.IOException; -import java.io.InputStream; -import java.net.URL; -import java.nio.file.Files; -import java.nio.file.Path; -import org.photonvision.common.hardware.PiVersion; -import org.photonvision.common.hardware.Platform; -import org.photonvision.common.logging.LogGroup; -import org.photonvision.common.logging.Logger; - -public class PicamJNI { - private static boolean libraryLoaded = false; - private static boolean enabled = - false; // TODO once we've sorted out what apriltags needs to be doing, we can bring this back? - private static Logger logger = new Logger(PicamJNI.class, LogGroup.Camera); - - public enum SensorModel { - Disconnected, - OV5647, // Picam v1 - IMX219, // Picam v2 - IMX477, // Picam HQ - Unknown; - - public String getFriendlyName() { - switch (this) { - case Disconnected: - return "Disconnected Camera"; - case OV5647: - return "Camera Module v1"; - case IMX219: - return "Camera Module v2"; - case IMX477: - return "HQ Camera"; - case Unknown: - default: - return "Unknown Camera"; - } - } - } - - public static synchronized void forceLoad() throws IOException { - if (libraryLoaded || !Platform.isRaspberryPi()) return; - - try { - File libDirectory = Path.of("lib/").toFile(); - if (!libDirectory.exists()) { - Files.createDirectory(libDirectory.toPath()).toFile(); - } - - // We always extract the shared object (we could hash each so, but that's a lot of work) - URL resourceURL = PicamJNI.class.getResource("/nativelibraries/libpicam.so"); - File libFile = Path.of("lib/libpicam.so").toFile(); - try (InputStream in = resourceURL.openStream()) { - if (libFile.exists()) Files.delete(libFile.toPath()); - Files.copy(in, libFile.toPath()); - } catch (Exception e) { - logger.error("Could not extract the native library!"); - } - System.load(libFile.getAbsolutePath()); - - libraryLoaded = true; - logger.info("Successfully loaded libpicam shared object"); - } catch (UnsatisfiedLinkError e) { - logger.error("Couldn't load libpicam shared object"); - e.printStackTrace(); - } - } - - public static boolean isSupported() { - var piVer = PiVersion.getPiVersion(); - - boolean hwSupported = - (piVer == PiVersion.PI_3 - || piVer == PiVersion.COMPUTE_MODULE_3 - || piVer == PiVersion.ZERO_2_W); - - return libraryLoaded - && enabled - && isVCSMSupported() - && getSensorModel() != SensorModel.Disconnected - && hwSupported; - } - - public static SensorModel getSensorModel() { - switch (getSensorModelRaw().toLowerCase()) { - case "": - return SensorModel.Disconnected; - case "ov5647": - return SensorModel.OV5647; - case "imx219": - return SensorModel.IMX219; - case "imx477": - return SensorModel.IMX477; - default: - return SensorModel.Unknown; - } - } - - private static native String getSensorModelRaw(); - - // This is the main thing we need that isn't supported on Pi 4s, which makes it a good check - private static native boolean isVCSMSupported(); - - // Everything here is static because multiple picams are unsupported at the hardware level - - /** - * Called once for each video mode change. Starts a native thread running MMAL that stays alive - * until destroyCamera is called. - * - * @return true on error. - */ - public static native boolean createCamera(int width, int height, int fps); - - /** - * Destroys MMAL and EGL contexts. Called once for each video mode change *before* createCamera. - * - * @return true on error. - */ - public static native boolean destroyCamera(); - - public static native void setThresholds( - double hL, double sL, double vL, double hU, double sU, double vU); - - public static native void setInvertHue(boolean shouldInvert); - - public static native boolean setExposure(int exposure); - - public static native boolean setBrightness(int brightness); - - // This adjusts the analog gain (normalized to 0-100); ignores the digital gain - public static native boolean setGain(int gain); - - // Adjusts the auto white balance gains, which are normalized 0-100 in the native code - public static native boolean setAwbGain(int red, int blue); - - public static native boolean setRotation(int rotation); - - public static native void setShouldCopyColor(boolean shouldCopyColor); - - public static native long getFrameLatency(); - - public static native long grabFrame(boolean shouldReturnColor); -} diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java new file mode 100644 index 000000000..33341e72b --- /dev/null +++ b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java @@ -0,0 +1,220 @@ +/* + * 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 . + */ + +package org.photonvision.vision.camera; + +import edu.wpi.first.cscore.VideoMode; +import edu.wpi.first.math.Pair; +import java.util.HashMap; +import org.photonvision.common.configuration.CameraConfiguration; +import org.photonvision.common.util.math.MathUtils; +import org.photonvision.raspi.LibCameraJNI; +import org.photonvision.vision.camera.LibcameraGpuSource.FPSRatedVideoMode; +import org.photonvision.vision.opencv.ImageRotationMode; +import org.photonvision.vision.processes.VisionSourceSettables; + +public class LibcameraGpuSettables extends VisionSourceSettables { + private FPSRatedVideoMode currentVideoMode; + private double lastExposure = 50; + private int lastBrightness = 50; + private boolean lastExposureMode; + private int lastGain = 50; + private Pair lastAwbGains = new Pair<>(18, 18); + private boolean m_initialized = false; + + private ImageRotationMode m_rotationMode; + + public void setRotation(ImageRotationMode rotationMode) { + if (rotationMode != m_rotationMode) { + m_rotationMode = rotationMode; + + setVideoModeInternal(getCurrentVideoMode()); + } + } + + public LibcameraGpuSettables(CameraConfiguration configuration) { + super(configuration); + + videoModes = new HashMap<>(); + + LibCameraJNI.SensorModel sensorModel = LibCameraJNI.getSensorModel(); + + if (sensorModel == LibCameraJNI.SensorModel.IMX219) { + // Settings for the IMX219 sensor, which is used on the Pi Camera Module v2 + videoModes.put( + 0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 120, 120, .39)); + videoModes.put( + 1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, .39)); + videoModes.put( + 2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39)); + videoModes.put( + 3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 30, 30, .39)); + // TODO: fix 1280x720 in the native code and re-add it + videoModes.put( + 4, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, .53)); + videoModes.put( + 5, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 3280 / 2, 2464 / 2, 15, 20, 1)); + videoModes.put( + 6, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 3280 / 4, 2464 / 4, 15, 20, 1)); + } else if (sensorModel == LibCameraJNI.SensorModel.OV9281) { + videoModes.put( + 0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 800, 60, 60, 1)); + videoModes.put( + 1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280 / 2, 800 / 2, 60, 60, 1)); + videoModes.put( + 2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, .39)); + videoModes.put( + 3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39)); + } else { + if (sensorModel == LibCameraJNI.SensorModel.IMX477) { + LibcameraGpuSource.logger.warn( + "It appears you are using a Pi HQ Camera. This camera is not officially supported. You will have to set your camera FOV differently based on resolution."); + } else if (sensorModel == LibCameraJNI.SensorModel.Unknown) { + LibcameraGpuSource.logger.warn( + "You have an unknown sensor connected to your Pi over CSI! This is likely a bug. If it is not, then you will have to set your camera FOV differently based on resolution."); + } + + // Settings for the OV5647 sensor, which is used by the Pi Camera Module v1 + videoModes.put(0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 90, 90, 1)); + videoModes.put(1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 85, 90, 1)); + videoModes.put( + 2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 960, 720, 45, 49, 0.74)); + // Half the size of the active areas on the OV5647 + videoModes.put( + 3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 2592 / 2, 1944 / 2, 20, 20, 1)); + videoModes.put( + 4, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 720, 30, 45, 0.91)); + videoModes.put( + 5, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, 0.72)); + } + + // TODO need to add more video modes for new sensors here + + currentVideoMode = (FPSRatedVideoMode) videoModes.get(0); + } + + @Override + public double getFOV() { + return getCurrentVideoMode().fovMultiplier * getConfiguration().FOV; + } + + @Override + public void setAutoExposure(boolean cameraAutoExposure) { + lastExposureMode = cameraAutoExposure; + // TODO (Matt) -- call LibCameraJNI's auto exposure function, when that exists + LibCameraJNI.setAutoExposure(cameraAutoExposure); + } + + @Override + public void setExposure(double exposure) { + // Todo (Chris) - for now, handle auto exposure by using -1 + if (exposure < 0.0) { + exposure = -1; + } + + // TODO convert to uS + lastExposure = exposure; + var success = LibCameraJNI.setExposure((int) Math.round(exposure) * 800); + if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera exposure"); + } + + @Override + public void setBrightness(int brightness) { + lastBrightness = brightness; + double realBrightness = MathUtils.map(brightness, 0.0, 100.0, -1.0, 1.0); + var success = LibCameraJNI.setBrightness(realBrightness); + if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera brightness"); + } + + @Override + public void setGain(int gain) { + lastGain = gain; + // TODO units here seem odd -- 5ish seems legit? So divide by 10 + var success = LibCameraJNI.setAnalogGain(gain / 10.0); + if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera gain"); + } + + @Override + public void setRedGain(int red) { + lastAwbGains = Pair.of(red, lastAwbGains.getSecond()); + setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond()); + } + + @Override + public void setBlueGain(int blue) { + lastAwbGains = Pair.of(lastAwbGains.getFirst(), blue); + setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond()); + } + + public void setAwbGain(int red, int blue) { + var success = LibCameraJNI.setAwbGain(red / 10.0, blue / 10.0); + if (!success) LibcameraGpuSource.logger.warn("Couldn't set Pi Camera AWB gains"); + } + + @Override + public FPSRatedVideoMode getCurrentVideoMode() { + return currentVideoMode; + } + + @Override + protected void setVideoModeInternal(VideoMode videoMode) { + var mode = (FPSRatedVideoMode) videoMode; + + // We need to make sure that other threads don't try to do anything funny while we're recreating + // the camera + synchronized (LibCameraJNI.CAMERA_LOCK) { + boolean success = false; + if (m_initialized) { + success |= LibCameraJNI.stopCamera(); + success |= LibCameraJNI.destroyCamera(); + } + + // if (!success) { + // throw new RuntimeException( + // "Couldn't destroy a zero copy Pi Camera while switching video modes"); + // } + + System.out.println("Starting camera"); + success |= + LibCameraJNI.createCamera( + mode.width, mode.height, (m_rotationMode == ImageRotationMode.DEG_180 ? 180 : 0)); + success |= LibCameraJNI.startCamera(); + if (!success) { + throw new RuntimeException( + "Couldn't create a zero copy Pi Camera while switching video modes"); + } + m_initialized = true; + } + + // We don't store last settings on the native side, and when you change video mode these get + // reset on MMAL's end + setExposure(lastExposure); + setAutoExposure(lastExposureMode); + setBrightness(lastBrightness); + setGain(lastGain); + setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond()); + + LibCameraJNI.setFramesToCopy(true, true); + + currentVideoMode = mode; + } + + @Override + public HashMap getAllVideoModes() { + return videoModes; + } +} diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSource.java new file mode 100644 index 000000000..7e4330e4d --- /dev/null +++ b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSource.java @@ -0,0 +1,87 @@ +/* + * 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 . + */ + +package org.photonvision.vision.camera; + +import edu.wpi.first.cscore.VideoMode; +import org.photonvision.common.configuration.CameraConfiguration; +import org.photonvision.common.configuration.ConfigManager; +import org.photonvision.common.logging.LogGroup; +import org.photonvision.common.logging.Logger; +import org.photonvision.vision.frame.FrameProvider; +import org.photonvision.vision.frame.provider.LibcameraGpuFrameProvider; +import org.photonvision.vision.processes.VisionSource; +import org.photonvision.vision.processes.VisionSourceSettables; + +public class LibcameraGpuSource extends VisionSource { + static final Logger logger = new Logger(LibcameraGpuSource.class, LogGroup.Camera); + + private final LibcameraGpuSettables settables; + private final LibcameraGpuFrameProvider frameProvider; + + public LibcameraGpuSource(CameraConfiguration configuration) { + super(configuration); + if (configuration.cameraType != CameraType.ZeroCopyPicam) { + throw new IllegalArgumentException( + "GPUAcceleratedPicamSource only accepts CameraConfigurations with type Picam"); + } + + settables = new LibcameraGpuSettables(configuration); + frameProvider = new LibcameraGpuFrameProvider(settables); + } + + @Override + public FrameProvider getFrameProvider() { + return frameProvider; + } + + @Override + public VisionSourceSettables getSettables() { + return settables; + } + + /** + * On the OV5649 the actual FPS we want to request from the GPU can be higher than the FPS that we + * can do after processing. On the IMX219 these FPSes match pretty closely, except for the + * 1280x720 mode. We use this to present a rated FPS to the user that's lower than the actual FPS + * we request from the GPU. This is important for setting user expectations, and is also used by + * the frontend to detect and explain FPS drops. This class should ONLY be used by Picam video + * modes! This is to make sure it shows up nice in the frontend + */ + public static class FPSRatedVideoMode extends VideoMode { + public final int fpsActual; + public final double fovMultiplier; + + public FPSRatedVideoMode( + PixelFormat pixelFormat, + int width, + int height, + int ratedFPS, + int actualFPS, + double fovMultiplier) { + super(pixelFormat, width, height, ratedFPS); + + this.fpsActual = actualFPS; + this.fovMultiplier = fovMultiplier; + } + } + + @Override + public boolean isVendorCamera() { + return ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV(); + } +} diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/ZeroCopyPicamSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/ZeroCopyPicamSource.java deleted file mode 100644 index c7e980696..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/camera/ZeroCopyPicamSource.java +++ /dev/null @@ -1,234 +0,0 @@ -/* - * 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 . - */ - -package org.photonvision.vision.camera; - -import edu.wpi.first.cscore.VideoMode; -import edu.wpi.first.math.Pair; -import java.util.HashMap; -import org.photonvision.common.configuration.CameraConfiguration; -import org.photonvision.common.configuration.ConfigManager; -import org.photonvision.common.logging.LogGroup; -import org.photonvision.common.logging.Logger; -import org.photonvision.raspi.PicamJNI; -import org.photonvision.vision.frame.FrameProvider; -import org.photonvision.vision.frame.provider.AcceleratedPicamFrameProvider; -import org.photonvision.vision.processes.VisionSource; -import org.photonvision.vision.processes.VisionSourceSettables; - -public class ZeroCopyPicamSource extends VisionSource { - private static final Logger logger = new Logger(ZeroCopyPicamSource.class, LogGroup.Camera); - - private final VisionSourceSettables settables; - private final AcceleratedPicamFrameProvider frameProvider; - - public ZeroCopyPicamSource(CameraConfiguration configuration) { - super(configuration); - if (configuration.cameraType != CameraType.ZeroCopyPicam) { - throw new IllegalArgumentException( - "GPUAcceleratedPicamSource only accepts CameraConfigurations with type Picam"); - } - - settables = new PicamSettables(configuration); - frameProvider = new AcceleratedPicamFrameProvider(settables); - } - - @Override - public FrameProvider getFrameProvider() { - return frameProvider; - } - - @Override - public VisionSourceSettables getSettables() { - return settables; - } - - /** - * On the OV5649 the actual FPS we want to request from the GPU can be higher than the FPS that we - * can do after processing. On the IMX219 these FPSes match pretty closely, except for the - * 1280x720 mode. We use this to present a rated FPS to the user that's lower than the actual FPS - * we request from the GPU. This is important for setting user expectations, and is also used by - * the frontend to detect and explain FPS drops. This class should ONLY be used by Picam video - * modes! This is to make sure it shows up nice in the frontend - */ - public static class FPSRatedVideoMode extends VideoMode { - public final int fpsActual; - public final double fovMultiplier; - - public FPSRatedVideoMode( - PixelFormat pixelFormat, - int width, - int height, - int ratedFPS, - int actualFPS, - double fovMultiplier) { - super(pixelFormat, width, height, ratedFPS); - - this.fpsActual = actualFPS; - this.fovMultiplier = fovMultiplier; - } - } - - public static class PicamSettables extends VisionSourceSettables { - private FPSRatedVideoMode currentVideoMode; - private double lastExposure = 50; - private int lastBrightness = 50; - private boolean lastExposureMode; - private int lastGain = 50; - private Pair lastAwbGains = new Pair(18, 18); - - public PicamSettables(CameraConfiguration configuration) { - super(configuration); - - videoModes = new HashMap<>(); - PicamJNI.SensorModel sensorModel = PicamJNI.getSensorModel(); - - if (sensorModel == PicamJNI.SensorModel.IMX219) { - // Settings for the IMX219 sensor, which is used on the Pi Camera Module v2 - videoModes.put( - 0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 120, 120, .39)); - videoModes.put( - 1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, .39)); - videoModes.put( - 2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39)); - videoModes.put( - 3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 30, 30, .39)); - // TODO: fix 1280x720 in the native code and re-add it - videoModes.put( - 4, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, .53)); - } else { - if (sensorModel == PicamJNI.SensorModel.IMX477) { - logger.warn( - "It appears you are using a Pi HQ Camera. This camera is not officially supported. You will have to set your camera FOV differently based on resolution."); - } else if (sensorModel == PicamJNI.SensorModel.Unknown) { - logger.warn( - "You have an unknown sensor connected to your Pi over CSI! This is likely a bug. If it is not, then you will have to set your camera FOV differently based on resolution."); - } - - // Settings for the OV5647 sensor, which is used by the Pi Camera Module v1 - videoModes.put( - 0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 90, 90, 1)); - videoModes.put( - 1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, 1)); - videoModes.put( - 2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 85, 90, 1)); - videoModes.put( - 3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 30, 30, 1)); - videoModes.put( - 4, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 960, 720, 45, 49, 0.74)); - videoModes.put( - 5, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 720, 30, 45, 0.91)); - videoModes.put( - 6, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, 0.72)); - } - - currentVideoMode = (FPSRatedVideoMode) videoModes.get(0); - } - - @Override - public double getFOV() { - return getCurrentVideoMode().fovMultiplier * getConfiguration().FOV; - } - - @Override - public void setAutoExposure(boolean cameraAutoExposure) { - lastExposureMode = cameraAutoExposure; - // TODO (Matt) -- call PicamJNI's auto exposure function, when that exists - } - - @Override - public void setExposure(double exposure) { - // Todo (Chris) - for now, handle auto exposure by using 100% exposure - if (exposure < 0.0) { - exposure = 100.0; - } - - lastExposure = exposure; - var failure = PicamJNI.setExposure((int) Math.round(exposure)); - if (failure) logger.warn("Couldn't set Pi Camera exposure"); - } - - @Override - public void setBrightness(int brightness) { - lastBrightness = brightness; - var failure = PicamJNI.setBrightness(brightness); - if (failure) logger.warn("Couldn't set Pi Camera brightness"); - } - - @Override - public void setGain(int gain) { - lastGain = gain; - var failure = PicamJNI.setGain(gain); - if (failure) logger.warn("Couldn't set Pi Camera gain"); - } - - @Override - public void setRedGain(int red) { - lastAwbGains = Pair.of(red, lastAwbGains.getSecond()); - setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond()); - } - - @Override - public void setBlueGain(int blue) { - lastAwbGains = Pair.of(lastAwbGains.getFirst(), blue); - setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond()); - } - - public void setAwbGain(int red, int blue) { - var failure = PicamJNI.setAwbGain(red, blue); - if (failure) logger.warn("Couldn't set Pi Camera AWB gains"); - } - - @Override - public FPSRatedVideoMode getCurrentVideoMode() { - return currentVideoMode; - } - - @Override - protected void setVideoModeInternal(VideoMode videoMode) { - var mode = (FPSRatedVideoMode) videoMode; - var failure = PicamJNI.destroyCamera(); - if (failure) - throw new RuntimeException( - "Couldn't destroy a zero copy Pi Camera while switching video modes"); - failure = PicamJNI.createCamera(mode.width, mode.height, mode.fpsActual); - if (failure) - throw new RuntimeException( - "Couldn't create a zero copy Pi Camera while switching video modes"); - - // We don't store last settings on the native side, and when you change video mode these get - // reset on MMAL's end - setExposure(lastExposure); - setAutoExposure(lastExposureMode); - setBrightness(lastBrightness); - setGain(lastGain); - setAwbGain(lastAwbGains.getFirst(), lastAwbGains.getSecond()); - - currentVideoMode = mode; - } - - @Override - public HashMap getAllVideoModes() { - return videoModes; - } - } - - @Override - public boolean isVendorCamera() { - return ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV(); - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/Frame.java b/photon-core/src/main/java/org/photonvision/vision/frame/Frame.java index b20445099..d4202f77a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/Frame.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/Frame.java @@ -17,52 +17,58 @@ package org.photonvision.vision.frame; -import org.opencv.core.CvType; -import org.opencv.core.Mat; -import org.opencv.core.Size; import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.opencv.Releasable; public class Frame implements Releasable { public final long timestampNanos; - public final CVMat image; + + // Frame should at _least_ contain the thresholded frame, and sometimes the color image + public final CVMat colorImage; + public final CVMat processedImage; + public final FrameThresholdType type; + public final FrameStaticProperties frameStaticProperties; - public Frame(CVMat image, long timestampNanos, FrameStaticProperties frameStaticProperties) { - this.image = image; + public Frame( + CVMat color, + CVMat processed, + FrameThresholdType type, + long timestampNanos, + FrameStaticProperties frameStaticProperties) { + this.colorImage = color; + this.processedImage = processed; + this.type = type; this.timestampNanos = timestampNanos; this.frameStaticProperties = frameStaticProperties; } - public Frame(CVMat image, FrameStaticProperties frameStaticProperties) { - this(image, MathUtils.wpiNanoTime(), frameStaticProperties); + public Frame( + CVMat color, + CVMat processed, + FrameThresholdType processType, + FrameStaticProperties frameStaticProperties) { + this(color, processed, processType, MathUtils.wpiNanoTime(), frameStaticProperties); } public Frame() { - this(new CVMat(), MathUtils.wpiNanoTime(), new FrameStaticProperties(0, 0, 0, null)); - } - - public static Frame emptyFrame(int width, int height) { - return new Frame( - new CVMat(Mat.zeros(new Size(width, height), CvType.CV_8UC3)), + this( + new CVMat(), + new CVMat(), + FrameThresholdType.NONE, MathUtils.wpiNanoTime(), - new FrameStaticProperties(width, height, 0, null)); + new FrameStaticProperties(0, 0, 0, null)); } public void copyTo(Frame destFrame) { - image.getMat().copyTo(destFrame.image.getMat()); - } - - public static Frame copyFromAndRelease(Frame frame) { - var mat = new CVMat(); - frame.image.copyTo(mat); - frame.release(); - return new Frame(mat, frame.timestampNanos, frame.frameStaticProperties); + colorImage.getMat().copyTo(destFrame.colorImage.getMat()); + processedImage.getMat().copyTo(destFrame.processedImage.getMat()); } @Override public void release() { - image.release(); + colorImage.release(); + processedImage.release(); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java index 22b4e178f..3c405632d 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java @@ -18,7 +18,21 @@ package org.photonvision.vision.frame; import java.util.function.Supplier; +import org.photonvision.vision.opencv.ImageRotationMode; +import org.photonvision.vision.pipe.impl.HSVPipe; public interface FrameProvider extends Supplier { String getName(); + + /** Ask the camera to produce a certain kind of processed image (eg HSV or greyscale) */ + public void requestFrameThresholdType(FrameThresholdType type); + + /** Ask the camera to rotate frames it outputs */ + public void requestFrameRotation(ImageRotationMode rotationMode); + + /** Ask the camera to provide either the input, output, or both frames. */ + public void requestFrameCopies(boolean copyInput, boolean copyOutput); + + /** Ask the camera to rotate frames it outputs */ + public void requestHsvSettings(HSVPipe.HSVParams params); } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/NetworkFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/FrameThresholdType.java similarity index 58% rename from photon-core/src/main/java/org/photonvision/vision/frame/provider/NetworkFrameProvider.java rename to photon-core/src/main/java/org/photonvision/vision/frame/FrameThresholdType.java index 26cf1aca3..4e779f3c0 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/NetworkFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/FrameThresholdType.java @@ -15,22 +15,10 @@ * along with this program. If not, see . */ -package org.photonvision.vision.frame.provider; +package org.photonvision.vision.frame; -import org.apache.commons.lang3.NotImplementedException; -import org.photonvision.vision.frame.Frame; -import org.photonvision.vision.frame.FrameProvider; - -public class NetworkFrameProvider implements FrameProvider { - private int count = 0; - - @Override - public Frame get() { - throw new NotImplementedException(""); - } - - @Override - public String getName() { - return "NetworkFrameProvider" + count++; - } +public enum FrameThresholdType { + NONE, + HSV, + GREYSCALE, } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java index cd2f25f13..3a1848c9a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java @@ -31,9 +31,9 @@ import org.photonvision.common.dataflow.networktables.NetworkTablesManager; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.common.util.TimedTaskManager; -import org.photonvision.vision.frame.Frame; +import org.photonvision.vision.opencv.CVMat; -public class FileSaveFrameConsumer implements Consumer { +public class FileSaveFrameConsumer implements Consumer { // Formatters to generate unique, timestamped file names private static String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString(); private static String FILE_EXTENSION = ".jpg"; @@ -62,8 +62,8 @@ public class FileSaveFrameConsumer implements Consumer { this.logger = new Logger(FileSaveFrameConsumer.class, this.camNickname, LogGroup.General); } - public void accept(Frame frame) { - if (frame != null && !frame.image.getMat().empty()) { + public void accept(CVMat image) { + if (image != null && image.getMat() != null && !image.getMat().empty()) { if (lock.tryLock()) { boolean curCommand = entry.get(false); if (curCommand && !prevCommand) { @@ -78,7 +78,7 @@ public class FileSaveFrameConsumer implements Consumer { + tf.format(now) + FILE_EXTENSION; - Imgcodecs.imwrite(savefile, frame.image.getMat()); + Imgcodecs.imwrite(savefile, image.getMat()); // Help the user a bit - set the NT entry back to false after 500ms TimedTaskManager.getInstance().addOneShotTask(this::resetCommand, CMD_RESET_TIME_MS); diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java index 129519675..b070e372d 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java @@ -28,7 +28,7 @@ import org.opencv.core.Point; import org.opencv.core.Rect; import org.opencv.imgproc.Imgproc; import org.photonvision.common.util.ColorHelper; -import org.photonvision.vision.frame.Frame; +import org.photonvision.vision.opencv.CVMat; public class MJPGFrameConsumer { public static final Mat EMPTY_MAT = new Mat(60, 15 * 7, CvType.CV_8UC3); @@ -167,9 +167,9 @@ public class MJPGFrameConsumer { this(name, 320, 240, port); } - public void accept(Frame frame) { - if (frame != null && !frame.image.getMat().empty()) { - cvSource.putFrame(frame.image.getMat()); + public void accept(CVMat image) { + if (image != null && !image.getMat().empty()) { + cvSource.putFrame(image.getMat()); // Make sure our disabled framerate limiting doesn't get confused isDisabled = false; diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProvider.java deleted file mode 100644 index 050fb3fef..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProvider.java +++ /dev/null @@ -1,60 +0,0 @@ -/* - * 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 . - */ - -package org.photonvision.vision.frame.provider; - -import org.opencv.core.Mat; -import org.photonvision.common.util.math.MathUtils; -import org.photonvision.raspi.PicamJNI; -import org.photonvision.vision.frame.Frame; -import org.photonvision.vision.frame.FrameProvider; -import org.photonvision.vision.opencv.CVMat; -import org.photonvision.vision.processes.VisionSourceSettables; - -public class AcceleratedPicamFrameProvider implements FrameProvider { - private final VisionSourceSettables settables; - - private CVMat mat; - - public AcceleratedPicamFrameProvider(VisionSourceSettables visionSettables) { - this.settables = visionSettables; - - var vidMode = settables.getCurrentVideoMode(); - var failure = PicamJNI.createCamera(vidMode.width, vidMode.height, vidMode.fps); - if (failure) { - failure = PicamJNI.destroyCamera(); - if (failure) throw new RuntimeException("Couldn't destroy Pi camera after init failure!"); - throw new RuntimeException( - "Couldn't initialize zero copy Pi camera; check stdout for native code logs"); - } - } - - @Override - public String getName() { - return "AcceleratedPicamFrameProvider"; - } - - @Override - public Frame get() { - long matHandle = PicamJNI.grabFrame(false); - mat = new CVMat(new Mat(matHandle)); - return new Frame( - mat, - MathUtils.wpiNanoTime() - PicamJNI.getFrameLatency(), - settables.getFrameStaticProperties()); - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java new file mode 100644 index 000000000..f9f28c0a5 --- /dev/null +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java @@ -0,0 +1,124 @@ +/* + * 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 . + */ + +package org.photonvision.vision.frame.provider; + +import org.photonvision.common.util.numbers.IntegerCouple; +import org.photonvision.vision.frame.Frame; +import org.photonvision.vision.frame.FrameProvider; +import org.photonvision.vision.frame.FrameStaticProperties; +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.GrayscalePipe; +import org.photonvision.vision.pipe.impl.HSVPipe; +import org.photonvision.vision.pipe.impl.RotateImagePipe; + +public abstract class CpuImageProcessor implements FrameProvider { + protected class CapturedFrame { + CVMat colorImage; + FrameStaticProperties staticProps; + long captureTimestamp; + + public CapturedFrame( + CVMat colorImage, FrameStaticProperties staticProps, long captureTimestampNanos) { + this.colorImage = colorImage; + this.staticProps = staticProps; + this.captureTimestamp = captureTimestampNanos; + } + } + + private final HSVPipe m_hsvPipe = new HSVPipe(); + private final RotateImagePipe m_rImagePipe = new RotateImagePipe(); + private final GrayscalePipe m_grayPipe = new GrayscalePipe(); + FrameThresholdType m_processType; + + private final Object m_mutex = new Object(); + + abstract CapturedFrame getInputMat(); + + public CpuImageProcessor() { + m_hsvPipe.setParams( + new HSVPipe.HSVParams( + new IntegerCouple(0, 180), + new IntegerCouple(0, 255), + new IntegerCouple(0, 255), + false)); + } + + @Override + public final Frame get() { + // TODO Auto-generated method stub + var input = getInputMat(); + + CVMat outputMat = null; + long sumNanos = 0; + + { + CVPipeResult out = m_rImagePipe.run(input.colorImage.getMat()); + sumNanos += out.nanosElapsed; + } + + if (!input.colorImage.getMat().empty()) { + if (m_processType == FrameThresholdType.HSV) { + var hsvResult = m_hsvPipe.run(input.colorImage.getMat()); + outputMat = new CVMat(hsvResult.output); + sumNanos += hsvResult.nanosElapsed; + } else if (m_processType == FrameThresholdType.GREYSCALE) { + var result = m_grayPipe.run(input.colorImage.getMat()); + outputMat = new CVMat(result.output); + sumNanos += result.nanosElapsed; + } else { + outputMat = new CVMat(); + } + } else { + System.out.println("Input was empty!"); + outputMat = new CVMat(); + } + + return new Frame( + input.colorImage, outputMat, m_processType, input.captureTimestamp, input.staticProps); + } + + @Override + public void requestFrameThresholdType(FrameThresholdType type) { + synchronized (m_mutex) { + this.m_processType = type; + } + } + + @Override + public void requestFrameRotation(ImageRotationMode rotationMode) { + synchronized (m_mutex) { + m_rImagePipe.setParams(new RotateImagePipe.RotateImageParams(rotationMode)); + } + } + + /** Ask the camera to rotate frames it outputs */ + public void requestHsvSettings(HSVPipe.HSVParams params) { + synchronized (m_mutex) { + m_hsvPipe.setParams(params); + } + } + + @Override + public void requestFrameCopies(boolean copyInput, boolean copyOutput) { + // We don't actually do zero-copy, so this method is a no-op + return; + } +} diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java index aa39bafa0..8c7272ba2 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java @@ -22,8 +22,8 @@ import java.nio.file.Path; import java.nio.file.Paths; import org.opencv.core.Mat; import org.opencv.imgcodecs.Imgcodecs; +import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.calibration.CameraCalibrationCoefficients; -import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameProvider; import org.photonvision.vision.frame.FrameStaticProperties; import org.photonvision.vision.opencv.CVMat; @@ -32,14 +32,14 @@ import org.photonvision.vision.opencv.CVMat; * A {@link FrameProvider} that will read and provide an image from a {@link java.nio.file.Path * path}. */ -public class FileFrameProvider implements FrameProvider { +public class FileFrameProvider extends CpuImageProcessor { public static final int MAX_FPS = 5; private static int count = 0; private final int thisIndex = count++; private final Path path; private final int millisDelay; - private final Frame originalFrame; + private final CVMat originalFrame; private final FrameStaticProperties properties; @@ -70,7 +70,7 @@ public class FileFrameProvider implements FrameProvider { Mat rawImage = Imgcodecs.imread(path.toString()); if (rawImage.cols() > 0 && rawImage.rows() > 0) { properties = new FrameStaticProperties(rawImage.width(), rawImage.height(), fov, calibration); - originalFrame = new Frame(new CVMat(rawImage), properties); + originalFrame = new CVMat(rawImage); } else { throw new RuntimeException("Image loading failed!"); } @@ -97,9 +97,9 @@ public class FileFrameProvider implements FrameProvider { } @Override - public Frame get() { - Frame outputFrame = new Frame(new CVMat(), properties); - originalFrame.copyTo(outputFrame); + public CapturedFrame getInputMat() { + var out = new CVMat(); + out.copyTo(originalFrame); // block to keep FPS at a defined rate if (System.currentTimeMillis() - lastGetMillis < millisDelay) { @@ -111,7 +111,7 @@ public class FileFrameProvider implements FrameProvider { } lastGetMillis = System.currentTimeMillis(); - return outputFrame; + return new CapturedFrame(out, properties, MathUtils.wpiNanoTime()); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java new file mode 100644 index 000000000..7b76f658a --- /dev/null +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java @@ -0,0 +1,114 @@ +/* + * 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 . + */ + +package org.photonvision.vision.frame.provider; + +import org.opencv.core.Mat; +import org.photonvision.common.util.math.MathUtils; +import org.photonvision.raspi.LibCameraJNI; +import org.photonvision.vision.camera.LibcameraGpuSettables; +import org.photonvision.vision.frame.Frame; +import org.photonvision.vision.frame.FrameProvider; +import org.photonvision.vision.frame.FrameThresholdType; +import org.photonvision.vision.opencv.CVMat; +import org.photonvision.vision.opencv.ImageRotationMode; +import org.photonvision.vision.pipe.impl.HSVPipe.HSVParams; + +public class LibcameraGpuFrameProvider implements FrameProvider { + private final LibcameraGpuSettables settables; + + public LibcameraGpuFrameProvider(LibcameraGpuSettables visionSettables) { + this.settables = visionSettables; + + var vidMode = settables.getCurrentVideoMode(); + settables.setVideoMode(vidMode); + } + + @Override + public String getName() { + return "AcceleratedPicamFrameProvider"; + } + + int i = 0; + + @Override + public Frame get() { + // We need to make sure that other threads don't try to change video modes while we're waiting + // for a frame + // System.out.println("GET!"); + synchronized (LibCameraJNI.CAMERA_LOCK) { + var success = LibCameraJNI.awaitNewFrame(); + + if (!success) { + System.out.println("No new frame"); + return new Frame(); + } + + var colorMat = new CVMat(new Mat(LibCameraJNI.takeColorFrame())); + var processedMat = new CVMat(new Mat(LibCameraJNI.takeProcessedFrame())); + + // System.out.println("Color mat: " + colorMat.getMat().size()); + + // Imgcodecs.imwrite("color" + i + ".jpg", colorMat.getMat()); + // Imgcodecs.imwrite("processed" + (i) + ".jpg", processedMat.getMat()); + + int itype = LibCameraJNI.getGpuProcessType(); + FrameThresholdType type = FrameThresholdType.NONE; + if (itype < FrameThresholdType.values().length && itype >= 0) { + type = FrameThresholdType.values()[itype]; + } + + var now = LibCameraJNI.getLibcameraTimestamp(); + var capture = LibCameraJNI.getFrameCaptureTime(); + var latency = (now - capture); + + return new Frame( + colorMat, + processedMat, + type, + MathUtils.wpiNanoTime() - latency, + settables.getFrameStaticProperties()); + } + } + + @Override + public void requestFrameThresholdType(FrameThresholdType type) { + LibCameraJNI.setGpuProcessType(type.ordinal()); + } + + @Override + public void requestFrameRotation(ImageRotationMode rotationMode) { + this.settables.setRotation(rotationMode); + } + + @Override + public void requestHsvSettings(HSVParams params) { + LibCameraJNI.setThresholds( + params.getHsvLower().val[0] / 180.0, + params.getHsvLower().val[1] / 255.0, + params.getHsvLower().val[2] / 255.0, + params.getHsvUpper().val[0] / 180.0, + params.getHsvUpper().val[1] / 255.0, + params.getHsvUpper().val[2] / 255.0, + params.getHueInverted()); + } + + @Override + public void requestFrameCopies(boolean copyInput, boolean copyOutput) { + LibCameraJNI.setFramesToCopy(copyInput, copyOutput); + } +} diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java index 232e3e301..03459c197 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/USBFrameProvider.java @@ -19,12 +19,10 @@ package org.photonvision.vision.frame.provider; import edu.wpi.first.cscore.CvSink; import org.photonvision.common.util.math.MathUtils; -import org.photonvision.vision.frame.Frame; -import org.photonvision.vision.frame.FrameProvider; import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.processes.VisionSourceSettables; -public class USBFrameProvider implements FrameProvider { +public class USBFrameProvider extends CpuImageProcessor { private final CvSink cvSink; @SuppressWarnings("SpellCheckingInspection") @@ -38,18 +36,19 @@ public class USBFrameProvider implements FrameProvider { } @Override - public Frame get() { + public CapturedFrame getInputMat() { var mat = new CVMat(); // We do this so that we don't fill a Mat in use by another thread // This is from wpi::Now, or WPIUtilJNI.now() long time = - cvSink.grabFrame( - mat.getMat()); // Units are microseconds, epoch is the same as the Unix epoch + cvSink.grabFrame(mat.getMat()) + * 1000; // Units are microseconds, epoch is the same as the Unix epoch // Sometimes CSCore gives us a zero frametime. if (time <= 1e-6) { time = MathUtils.wpiNanoTime(); } - return new Frame(mat, MathUtils.microsToNanos(time), settables.getFrameStaticProperties()); + + return new CapturedFrame(mat, settables.getFrameStaticProperties(), time); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java index 5f2662754..32ea2938b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java @@ -20,11 +20,11 @@ package org.photonvision.vision.pipe.impl; import edu.wpi.first.apriltag.AprilTagDetection; import edu.wpi.first.apriltag.AprilTagDetector; import java.util.List; -import org.opencv.core.Mat; +import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.pipe.CVPipe; public class AprilTagDetectionPipe - extends CVPipe, AprilTagDetectionPipeParams> { + extends CVPipe, AprilTagDetectionPipeParams> { private final AprilTagDetector m_detector = new AprilTagDetector(); boolean useNativePoseEst; @@ -37,8 +37,12 @@ public class AprilTagDetectionPipe } @Override - protected List process(Mat in) { - var ret = m_detector.detect(in); + protected List process(CVMat in) { + if (in.getMat().empty()) { + return List.of(); + } + + var ret = m_detector.detect(in.getMat()); if (ret == null) { return List.of(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java index 8ebd78d03..336dfef7a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java @@ -107,8 +107,8 @@ public class FilterContoursPipe // Fullness Filtering. double contourArea = contour.getArea(); - double minFullness = params.getFullness().getFirst() * minAreaRect.size.area() / 100; - double maxFullness = params.getFullness().getSecond() * minAreaRect.size.area() / 100; + double minFullness = params.getFullness().getFirst() * minAreaRect.size.area() / 100.0; + double maxFullness = params.getFullness().getSecond() * minAreaRect.size.area() / 100.0; if (contourArea <= minFullness || contourArea >= maxFullness) return; // Aspect Ratio Filtering. diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java index 4aa4594ae..e4d1efb99 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java @@ -24,12 +24,9 @@ import edu.wpi.first.math.geometry.Transform3d; import edu.wpi.first.math.util.Units; import java.util.ArrayList; import java.util.List; -import org.opencv.core.Mat; import org.photonvision.common.util.math.MathUtils; -import org.photonvision.raspi.PicamJNI; -import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.frame.Frame; -import org.photonvision.vision.opencv.CVMat; +import org.photonvision.vision.frame.FrameThresholdType; import org.photonvision.vision.pipe.CVPipe.CVPipeResult; import org.photonvision.vision.pipe.impl.*; import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams; @@ -39,17 +36,19 @@ import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters; @SuppressWarnings("DuplicatedCode") public class AprilTagPipeline extends CVPipeline { - private final RotateImagePipe rotateImagePipe = new RotateImagePipe(); - private final GrayscalePipe grayscalePipe = new GrayscalePipe(); private final AprilTagDetectionPipe aprilTagDetectionPipe = new AprilTagDetectionPipe(); private final AprilTagPoseEstimatorPipe poseEstimatorPipe = new AprilTagPoseEstimatorPipe(); private final CalculateFPSPipe calculateFPSPipe = new CalculateFPSPipe(); + private static final FrameThresholdType PROCESSING_TYPE = FrameThresholdType.GREYSCALE; + public AprilTagPipeline() { + super(PROCESSING_TYPE); settings = new AprilTagPipelineSettings(); } public AprilTagPipeline(AprilTagPipelineSettings settings) { + super(PROCESSING_TYPE); this.settings = settings; } @@ -58,15 +57,11 @@ public class AprilTagPipeline extends CVPipeline grayscalePipeResult; - Mat rawInputMat; - boolean inputSingleChannel = frame.image.getMat().channels() == 1; - - if (inputSingleChannel) { - rawInputMat = new Mat(PicamJNI.grabFrame(true)); - frame.image.getMat().release(); // release the 8bit frame ASAP. - } else { - rawInputMat = frame.image.getMat(); - var rotateImageResult = rotateImagePipe.run(rawInputMat); - sumPipeNanosElapsed += rotateImageResult.nanosElapsed; - } - - var inputFrame = new Frame(new CVMat(rawInputMat), frameStaticProperties); - - grayscalePipeResult = grayscalePipe.run(rawInputMat); - sumPipeNanosElapsed += grayscalePipeResult.nanosElapsed; - - var outputFrame = new Frame(new CVMat(grayscalePipeResult.output), frameStaticProperties); - List targetList; - CVPipeResult> tagDetectionPipeResult; // Use the solvePNP Enabled flag to enable native pose estimation aprilTagDetectionPipe.setNativePoseEstimationEnabled(settings.solvePNPEnabled); - tagDetectionPipeResult = aprilTagDetectionPipe.run(grayscalePipeResult.output); + if (frame.type != FrameThresholdType.GREYSCALE) { + // TODO so all cameras should give us ADAPTIVE_THRESH -- how should we handle if not? + return new CVPipelineResult(0, 0, List.of()); + } + + CVPipeResult> tagDetectionPipeResult; + tagDetectionPipeResult = aprilTagDetectionPipe.run(frame.processedImage); sumPipeNanosElapsed += tagDetectionPipeResult.nanosElapsed; targetList = new ArrayList<>(); @@ -194,6 +174,6 @@ public class AprilTagPipeline extends CVPipeline { @@ -28,6 +28,16 @@ public abstract class CVPipeline(); - hsvPipeResult.output = frame.image.getMat(); - hsvPipeResult.nanosElapsed = MathUtils.wpiNanoTime() - frame.timestampNanos; - - sumPipeNanosElapsed += hsvPipeResult.nanosElapsed; - } - // var erodeDilateResult = erodeDilatePipe.run(rawInputMat); // sumPipeNanosElapsed += erodeDilateResult.nanosElapsed; // // CVPipeResult hsvPipeResult = hsvPipe.run(rawInputMat); // sumPipeNanosElapsed += hsvPipeResult.nanosElapsed; - CVPipeResult> findContoursResult = findContoursPipe.run(hsvPipeResult.output); + CVPipeResult> findContoursResult = + findContoursPipe.run(frame.processedImage.getMat()); sumPipeNanosElapsed += findContoursResult.nanosElapsed; CVPipeResult> speckleRejectResult = @@ -247,7 +192,7 @@ public class ColoredShapePipeline List shapes = null; if (settings.contourShape == ContourShape.Circle) { CVPipeResult> findCirclesResult = - findCirclesPipe.run(Pair.of(hsvPipeResult.output, speckleRejectResult.output)); + findCirclesPipe.run(Pair.of(frame.processedImage.getMat(), speckleRejectResult.output)); sumPipeNanosElapsed += findCirclesResult.nanosElapsed; shapes = findCirclesResult.output; } else { @@ -293,11 +238,6 @@ public class ColoredShapePipeline var fpsResult = calculateFPSPipe.run(null); var fps = fpsResult.output; - return new CVPipelineResult( - sumPipeNanosElapsed, - fps, - targetList, - new Frame(new CVMat(hsvPipeResult.output), frame.frameStaticProperties), - new Frame(new CVMat(rawInputMat), frame.frameStaticProperties)); + return new CVPipelineResult(sumPipeNanosElapsed, fps, targetList, frame); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java index 844f6db86..a665f6415 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java @@ -19,12 +19,11 @@ package org.photonvision.vision.pipeline; import java.util.List; import org.apache.commons.lang3.tuple.Pair; -import org.opencv.core.Mat; import org.photonvision.common.util.math.MathUtils; -import org.photonvision.raspi.PicamJNI; +import org.photonvision.raspi.LibCameraJNI; import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.frame.Frame; -import org.photonvision.vision.opencv.CVMat; +import org.photonvision.vision.frame.FrameThresholdType; import org.photonvision.vision.pipe.impl.CalculateFPSPipe; import org.photonvision.vision.pipe.impl.Draw2dCrosshairPipe; import org.photonvision.vision.pipe.impl.ResizeImagePipe; @@ -38,10 +37,18 @@ public class DriverModePipeline private final CalculateFPSPipe calculateFPSPipe = new CalculateFPSPipe(); private final ResizeImagePipe resizeImagePipe = new ResizeImagePipe(); + private static final FrameThresholdType PROCESSING_TYPE = FrameThresholdType.NONE; + public DriverModePipeline() { + super(PROCESSING_TYPE); settings = new DriverModePipelineSettings(); } + public DriverModePipeline(DriverModePipelineSettings settings) { + super(PROCESSING_TYPE); + this.settings = settings; + } + @Override protected void setPipeParamsImpl() { RotateImagePipe.RotateImageParams rotateImageParams = @@ -56,25 +63,19 @@ public class DriverModePipeline resizeImagePipe.setParams( new ResizeImagePipe.ResizeImageParams(settings.streamingFrameDivisor)); - if (PicamJNI.isSupported() && cameraQuirks.hasQuirk(CameraQuirk.PiCam)) { - PicamJNI.setRotation(settings.inputImageRotationMode.value); - PicamJNI.setShouldCopyColor(true); - } + // if (LibCameraJNI.isSupported() && cameraQuirks.hasQuirk(CameraQuirk.PiCam)) { + // LibCameraJNI.setRotation(settings.inputImageRotationMode.value); + // LibCameraJNI.setShouldCopyColor(true); + // } } @Override public DriverModePipelineResult process(Frame frame, DriverModePipelineSettings settings) { long totalNanos = 0; - boolean accelerated = PicamJNI.isSupported() && cameraQuirks.hasQuirk(CameraQuirk.PiCam); + boolean accelerated = LibCameraJNI.isSupported() && cameraQuirks.hasQuirk(CameraQuirk.PiCam); // apply pipes - var inputMat = frame.image.getMat(); - if (inputMat.channels() == 1 && accelerated) { - long colorMatPtr = PicamJNI.grabFrame(true); - if (colorMatPtr == 0) throw new RuntimeException("Got null Mat from GPU Picam driver"); - frame.image.release(); - inputMat = new Mat(colorMatPtr); - } + var inputMat = frame.colorImage.getMat(); totalNanos += resizeImagePipe.run(inputMat).nanosElapsed; @@ -91,9 +92,10 @@ public class DriverModePipeline var fpsResult = calculateFPSPipe.run(null); var fps = fpsResult.output; + // Flip-flop input and output in the Frame return new DriverModePipelineResult( MathUtils.nanosToMillis(totalNanos), fps, - new Frame(new CVMat(inputMat), frame.frameStaticProperties)); + new Frame(frame.processedImage, frame.colorImage, frame.type, frame.frameStaticProperties)); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java index 5c0d9849f..8be13f757 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java @@ -21,7 +21,6 @@ import java.util.List; import org.apache.commons.lang3.tuple.Pair; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameStaticProperties; -import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.opencv.ContourShape; import org.photonvision.vision.opencv.DualOffsetValues; import org.photonvision.vision.pipe.impl.*; @@ -99,18 +98,19 @@ public class OutputStreamPipeline { } public CVPipelineResult process( - Frame inputFrame, - Frame outputFrame, + Frame inputAndOutputFrame, AdvancedPipelineSettings settings, List targetsToDraw) { - setPipeParams(inputFrame.frameStaticProperties, settings); - var inMat = inputFrame.image.getMat(); - var outMat = outputFrame.image.getMat(); + setPipeParams(inputAndOutputFrame.frameStaticProperties, settings); + var inMat = inputAndOutputFrame.colorImage.getMat(); + var outMat = inputAndOutputFrame.processedImage.getMat(); long sumPipeNanosElapsed = 0L; // Resize both in place before doing any conversion - sumPipeNanosElapsed += pipeProfileNanos[0] = resizeImagePipe.run(inMat).nanosElapsed; + boolean inEmpty = inMat.empty(); + if (!inEmpty) + sumPipeNanosElapsed += pipeProfileNanos[0] = resizeImagePipe.run(inMat).nanosElapsed; sumPipeNanosElapsed += pipeProfileNanos[1] = resizeImagePipe.run(outMat).nanosElapsed; // Convert single-channel HSV output mat to 3-channel BGR in preparation for streaming @@ -183,7 +183,6 @@ public class OutputStreamPipeline { sumPipeNanosElapsed, fps, // Unused but here just in case targetsToDraw, - new Frame(new CVMat(outMat), outputFrame.frameStaticProperties), - new Frame(new CVMat(inMat), inputFrame.frameStaticProperties)); + inputAndOutputFrame); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java index 8372904d4..cea2e3142 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java @@ -18,12 +18,8 @@ package org.photonvision.vision.pipeline; import java.util.List; -import org.opencv.core.Mat; -import org.photonvision.common.util.math.MathUtils; -import org.photonvision.raspi.PicamJNI; -import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.frame.Frame; -import org.photonvision.vision.opencv.CVMat; +import org.photonvision.vision.frame.FrameThresholdType; import org.photonvision.vision.opencv.Contour; import org.photonvision.vision.opencv.DualOffsetValues; import org.photonvision.vision.pipe.CVPipe.CVPipeResult; @@ -36,8 +32,6 @@ import org.photonvision.vision.target.TrackedTarget; /** Represents a pipeline for tracking retro-reflective targets. */ @SuppressWarnings({"DuplicatedCode"}) public class ReflectivePipeline extends CVPipeline { - private final RotateImagePipe rotateImagePipe = new RotateImagePipe(); - private final HSVPipe hsvPipe = new HSVPipe(); private final FindContoursPipe findContoursPipe = new FindContoursPipe(); private final SpeckleRejectPipe speckleRejectPipe = new SpeckleRejectPipe(); private final FilterContoursPipe filterContoursPipe = new FilterContoursPipe(); @@ -50,11 +44,15 @@ public class ReflectivePipeline extends CVPipeline hsvPipeResult; - Mat rawInputMat; - if (frame.image.getMat().channels() != 1) { - var rotateImageResult = rotateImagePipe.run(frame.image.getMat()); - sumPipeNanosElapsed += pipeProfileNanos[0] = rotateImageResult.nanosElapsed; - - rawInputMat = frame.image.getMat(); - - hsvPipeResult = hsvPipe.run(rawInputMat); - sumPipeNanosElapsed += hsvPipeResult.nanosElapsed; - pipeProfileNanos[1] = pipeProfileNanos[1] = hsvPipeResult.nanosElapsed; - } else { - // Try to copy the color frame. - long inputMatPtr = PicamJNI.grabFrame(true); - if (inputMatPtr != 0) { - // If we grabbed it (in color copy mode), make a new Mat of it - rawInputMat = new Mat(inputMatPtr); - } else { - // Otherwise, the input mat is frame we got from the camera - rawInputMat = frame.image.getMat(); - // // Otherwise, use a blank/empty mat as placeholder - // rawInputMat = new Mat(); - } - - // We can skip a few steps if the image is single channel because we've already done them on - // the GPU - hsvPipeResult = new CVPipeResult<>(); - hsvPipeResult.output = frame.image.getMat(); - hsvPipeResult.nanosElapsed = MathUtils.wpiNanoTime() - frame.timestampNanos; - - sumPipeNanosElapsed = pipeProfileNanos[1] = hsvPipeResult.nanosElapsed; - } - - CVPipeResult> findContoursResult = findContoursPipe.run(hsvPipeResult.output); + CVPipeResult> findContoursResult = + findContoursPipe.run(frame.processedImage.getMat()); sumPipeNanosElapsed += pipeProfileNanos[2] = findContoursResult.nanosElapsed; CVPipeResult> speckleRejectResult = @@ -226,11 +193,6 @@ public class ReflectivePipeline extends CVPipeline targets; - public final Frame outputFrame; - public final Frame inputFrame; + public final Frame inputAndOutputFrame; public CVPipelineResult( - double processingNanos, - double fps, - List targets, - Frame outputFrame, - Frame inputFrame) { + double processingNanos, double fps, List targets, Frame inputFrame) { this.processingNanos = processingNanos; this.fps = fps; this.targets = targets != null ? targets : Collections.emptyList(); - this.outputFrame = outputFrame; - this.inputFrame = inputFrame; + this.inputAndOutputFrame = inputFrame; } - public CVPipelineResult( - double processingNanos, double fps, List targets, Frame outputFrame) { - this(processingNanos, fps, targets, outputFrame, null); + public CVPipelineResult(double processingNanos, double fps, List targets) { + this(processingNanos, fps, targets, null); } public boolean hasTargets() { @@ -59,8 +52,7 @@ public class CVPipelineResult implements Releasable { for (TrackedTarget tt : targets) { tt.release(); } - outputFrame.release(); - if (inputFrame != null) inputFrame.release(); + if (inputAndOutputFrame != null) inputAndOutputFrame.release(); } /** @@ -68,6 +60,7 @@ public class CVPipelineResult implements Releasable { * the latency is relative to the time at which this method is called. Waiting to call this method * will change the latency this method returns. */ + @Deprecated public double getLatencyMillis() { var now = MathUtils.wpiNanoTime(); return MathUtils.nanosToMillis(now - imageCaptureTimestampNanos); diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java index 8d147bf0c..98fa1cba9 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java @@ -21,6 +21,7 @@ import edu.wpi.first.cscore.VideoException; import edu.wpi.first.math.util.Units; import io.javalin.websocket.WsContext; import java.util.*; +import java.util.function.BiConsumer; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.configuration.PhotonConfiguration; @@ -33,12 +34,11 @@ import org.photonvision.common.hardware.HardwareManager; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.common.util.SerializationUtils; -import org.photonvision.common.util.java.TriConsumer; import org.photonvision.vision.calibration.CameraCalibrationCoefficients; import org.photonvision.vision.camera.CameraQuirk; +import org.photonvision.vision.camera.LibcameraGpuSource; import org.photonvision.vision.camera.QuirkyCamera; import org.photonvision.vision.camera.USBCameraSource; -import org.photonvision.vision.camera.ZeroCopyPicamSource; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.consumer.FileSaveFrameConsumer; import org.photonvision.vision.pipeline.AdvancedPipelineSettings; @@ -65,7 +65,7 @@ public class VisionModule { private final StreamRunnable streamRunnable; private final LinkedList resultConsumers = new LinkedList<>(); // Raw result consumers run before any drawing has been done by the OutputStreamPipeline - private final LinkedList>> streamResultConsumers = + private final LinkedList>> streamResultConsumers = new LinkedList<>(); private final NTDataPublisher ntConsumer; private final UIDataPublisher uiDataConsumer; @@ -93,7 +93,7 @@ public class VisionModule { // Find quirks for the current camera if (visionSource instanceof USBCameraSource) { cameraQuirks = ((USBCameraSource) visionSource).cameraQuirks; - } else if (visionSource instanceof ZeroCopyPicamSource) { + } else if (visionSource instanceof LibcameraGpuSource) { cameraQuirks = QuirkyCamera.ZeroCopyPiCamera; } else { cameraQuirks = QuirkyCamera.DefaultCamera; @@ -190,17 +190,29 @@ public class VisionModule { } private void recreateStreamResultConsumers() { - streamResultConsumers.add((in, out, tgts) -> inputFrameSaver.accept(in)); - streamResultConsumers.add((in, out, tgts) -> outputFrameSaver.accept(out)); - streamResultConsumers.add((in, out, tgts) -> inputVideoStreamer.accept(in)); - streamResultConsumers.add((in, out, tgts) -> outputVideoStreamer.accept(out)); + streamResultConsumers.add( + (frame, tgts) -> { + if (frame != null) inputFrameSaver.accept(frame.colorImage); + }); + streamResultConsumers.add( + (frame, tgts) -> { + if (frame != null) outputFrameSaver.accept(frame.processedImage); + }); + streamResultConsumers.add( + (frame, tgts) -> { + if (frame != null) inputVideoStreamer.accept(frame.colorImage); + }); + streamResultConsumers.add( + (frame, tgts) -> { + if (frame != null) outputVideoStreamer.accept(frame.processedImage); + }); } private class StreamRunnable extends Thread { private final OutputStreamPipeline outputStreamPipeline; private final Object frameLock = new Object(); - private Frame inputFrame, outputFrame; + private Frame latestFrame; private AdvancedPipelineSettings settings = new AdvancedPipelineSettings(); private List targets = new ArrayList<>(); @@ -211,42 +223,35 @@ public class VisionModule { } public void updateData( - Frame inputFrame, - Frame outputFrame, - AdvancedPipelineSettings settings, - List targets) { + Frame inputOutputFrame, AdvancedPipelineSettings settings, List targets) { synchronized (frameLock) { - if (shouldRun && this.inputFrame != null && this.outputFrame != null) { + if (shouldRun && this.latestFrame != null) { logger.trace("Fell behind; releasing last unused Mats"); - this.inputFrame.release(); - this.outputFrame.release(); + this.latestFrame.release(); } - this.inputFrame = inputFrame; - this.outputFrame = outputFrame; + this.latestFrame = inputOutputFrame; this.settings = settings; this.targets = targets; - shouldRun = - inputFrame != null - && !inputFrame.image.getMat().empty() - && outputFrame != null - && !outputFrame.image.getMat().empty(); + shouldRun = inputOutputFrame != null; + // && inputOutputFrame.colorImage != null + // && !inputOutputFrame.colorImage.getMat().empty() + // && inputOutputFrame.processedImage != null + // && !inputOutputFrame.processedImage.getMat().empty(); } } @Override public void run() { while (true) { - final Frame inputFrame, outputFrame; + final Frame m_frame; final AdvancedPipelineSettings settings; final List targets; final boolean shouldRun; synchronized (frameLock) { - inputFrame = this.inputFrame; - outputFrame = this.outputFrame; - this.inputFrame = null; - this.outputFrame = null; + m_frame = this.latestFrame; + this.latestFrame = null; settings = this.settings; targets = this.targets; @@ -256,17 +261,15 @@ public class VisionModule { } if (shouldRun) { try { - CVPipelineResult osr = - outputStreamPipeline.process(inputFrame, outputFrame, settings, targets); - consumeResults(inputFrame, osr.outputFrame, targets); + CVPipelineResult osr = outputStreamPipeline.process(m_frame, settings, targets); + consumeResults(m_frame, targets); } catch (Exception e) { // Never die logger.error("Exception while running stream runnable!", e); } try { - inputFrame.release(); - outputFrame.release(); + m_frame.release(); } catch (Exception e) { logger.error("Exception freeing frames", e); } @@ -496,7 +499,7 @@ public class VisionModule { internalMap.put("fps", videoModes.get(k).fps); internalMap.put( "pixelFormat", - ((videoModes.get(k) instanceof ZeroCopyPicamSource.FPSRatedVideoMode) + ((videoModes.get(k) instanceof LibcameraGpuSource.FPSRatedVideoMode) ? "kPicam" : videoModes.get(k).pixelFormat.toString()) .substring(1)); // Remove the k prefix @@ -546,16 +549,15 @@ public class VisionModule { consumePipelineResult(result); // Pipelines like DriverMode and Calibrate3dPipeline have null output frames - if (result.inputFrame != null + if (result.inputAndOutputFrame != null && (pipelineManager.getCurrentPipelineSettings() instanceof AdvancedPipelineSettings)) { streamRunnable.updateData( - result.inputFrame, - result.outputFrame, + result.inputAndOutputFrame, (AdvancedPipelineSettings) pipelineManager.getCurrentPipelineSettings(), result.targets); // The streamRunnable manages releasing in this case } else { - consumeResults(result.inputFrame, result.outputFrame, result.targets); + consumeResults(result.inputAndOutputFrame, result.targets); result.release(); // In this case we don't bother with a separate streaming thread and we release @@ -569,9 +571,9 @@ public class VisionModule { } /** Consume stream/target results, no rate limiting applied */ - private void consumeResults(Frame inputFrame, Frame outputFrame, List targets) { + private void consumeResults(Frame frame, List targets) { for (var c : streamResultConsumers) { - c.accept(inputFrame, outputFrame, targets); + c.accept(frame, targets); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java index f4ba5d6e7..60acc0d39 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionRunner.java @@ -22,8 +22,9 @@ import java.util.function.Supplier; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.vision.camera.QuirkyCamera; -import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameProvider; +import org.photonvision.vision.pipe.impl.HSVPipe; +import org.photonvision.vision.pipeline.AdvancedPipelineSettings; import org.photonvision.vision.pipeline.CVPipeline; import org.photonvision.vision.pipeline.result.CVPipelineResult; @@ -32,7 +33,7 @@ import org.photonvision.vision.pipeline.result.CVPipelineResult; public class VisionRunner { private final Logger logger; private final Thread visionProcessThread; - private final Supplier frameSupplier; + private final FrameProvider frameSupplier; private final Supplier pipelineSupplier; private final Consumer pipelineResultConsumer; private final QuirkyCamera cameraQuirks; @@ -69,8 +70,29 @@ public class VisionRunner { private void update() { while (!Thread.interrupted()) { var pipeline = pipelineSupplier.get(); + + // Tell our camera implementation here what kind of pre-processing we need it to be doing + // (pipeline-dependent). I kinda hate how much leak this has... + // TODO would a callback object be a better fit? + var wantedProcessType = pipeline.getThresholdType(); + frameSupplier.requestFrameThresholdType(wantedProcessType); + var settings = pipeline.getSettings(); + if (settings instanceof AdvancedPipelineSettings) { + var advanced = (AdvancedPipelineSettings) settings; + var hsvParams = + new HSVPipe.HSVParams( + advanced.hsvHue, advanced.hsvSaturation, advanced.hsvValue, advanced.hueInverted); + // TODO who should deal with preventing this from happening _every single loop_? + frameSupplier.requestHsvSettings(hsvParams); + } + frameSupplier.requestFrameRotation(settings.inputImageRotationMode); + frameSupplier.requestFrameCopies(settings.inputShouldShow, settings.outputShouldShow); + + // Grab the new camera frame var frame = frameSupplier.get(); + // There's no guarantee the processing type change will occur this tick, so pipelines should + // check themselves try { var pipelineResult = pipeline.run(frame, cameraQuirks); pipelineResultConsumer.accept(pipelineResult); @@ -78,6 +100,7 @@ public class VisionRunner { logger.error("Exception on loop " + loopCount); ex.printStackTrace(); } + loopCount++; } } diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java index 35fb48b4b..81f216922 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java @@ -27,14 +27,15 @@ import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.dataflow.DataChangeService; import org.photonvision.common.dataflow.events.OutgoingUIEvent; +import org.photonvision.common.hardware.Platform; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.common.util.TimedTaskManager; -import org.photonvision.raspi.PicamJNI; +import org.photonvision.raspi.LibCameraJNI; import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.camera.CameraType; +import org.photonvision.vision.camera.LibcameraGpuSource; import org.photonvision.vision.camera.USBCameraSource; -import org.photonvision.vision.camera.ZeroCopyPicamSource; public class VisionSourceManager { private static final Logger logger = new Logger(VisionSourceManager.class, LogGroup.Camera); @@ -252,8 +253,14 @@ public class VisionSourceManager { logger.info("Creating a new camera config for camera " + uniqueName); + // HACK -- for picams, we want to use the camera model + String nickname = uniqueName; + if (isCsiCamera(info)) { + nickname = LibCameraJNI.getSensorModel().toString(); + } + CameraConfiguration configuration = - new CameraConfiguration(baseName, uniqueName, uniqueName, info.path); + new CameraConfiguration(baseName, uniqueName, nickname, info.path, info.otherPaths); cameraConfigurations.add(configuration); } @@ -261,6 +268,11 @@ public class VisionSourceManager { return cameraConfigurations; } + private boolean isCsiCamera(UsbCameraInfo configuration) { + return (Arrays.stream(configuration.otherPaths).anyMatch(it -> it.contains("csi-video")) + || cameraNameToBaseName(configuration.name).equals("unicam")); + } + private CameraConfiguration mergeInfoIntoConfig(CameraConfiguration cfg, UsbCameraInfo info) { if (!cfg.path.equals(info.path)) { logger.debug("Updating path config from " + cfg.path + " to " + info.path); @@ -307,20 +319,23 @@ public class VisionSourceManager { List camConfigs) { var cameraSources = new ArrayList(); for (var configuration : camConfigs) { - if (configuration.baseName.startsWith("mmal service") && PicamJNI.isSupported()) { - configuration.cameraType = CameraType.ZeroCopyPicam; - var piCamSrc = new ZeroCopyPicamSource(configuration); + System.out.println("Creating VisionSource for " + configuration); + // Picams should have csi-video in the path + boolean is_picam = + (Arrays.stream(configuration.otherPaths).anyMatch(it -> it.contains("csi-video")) + || configuration.baseName.equals("unicam")); + boolean is_pi = Platform.isRaspberryPi(); + if (is_picam && is_pi) { configuration.cameraType = CameraType.ZeroCopyPicam; + var piCamSrc = new LibcameraGpuSource(configuration); cameraSources.add(piCamSrc); - continue; - } - - var newCam = new USBCameraSource(configuration); - - if (!newCam.cameraQuirks.hasQuirk(CameraQuirk.CompletelyBroken) - && !newCam.getSettables().videoModes.isEmpty()) { - cameraSources.add(newCam); + } else { + var newCam = new USBCameraSource(configuration); + if (!newCam.cameraQuirks.hasQuirk(CameraQuirk.CompletelyBroken) + && !newCam.getSettables().videoModes.isEmpty()) { + cameraSources.add(newCam); + } } } return cameraSources; diff --git a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java index de72a8cf3..d4eef5e4f 100644 --- a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java +++ b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java @@ -25,10 +25,10 @@ import org.opencv.core.MatOfByte; import org.opencv.core.MatOfInt; import org.opencv.imgcodecs.Imgcodecs; import org.photonvision.common.util.math.MathUtils; -import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.consumer.MJPGFrameConsumer; +import org.photonvision.vision.opencv.CVMat; -public class SocketVideoStream implements Consumer { +public class SocketVideoStream implements Consumer { int portID = 0; // Align with cscore's port for unique identification of stream MatOfByte jpegBytes = null; @@ -55,7 +55,7 @@ public class SocketVideoStream implements Consumer { } @Override - public void accept(Frame frame) { + public void accept(CVMat image) { if (userCount > 0) { if (jpegBytesLock .tryLock()) { // we assume frames are coming in frequently. Just skip this frame if we're @@ -63,12 +63,12 @@ public class SocketVideoStream implements Consumer { try { // Does a single-shot frame recieve and convert to JPEG for efficency // Will not capture/convert again until convertNextFrame() is called - if (frame != null && !frame.image.getMat().empty() && jpegBytes == null) { + if (image != null && !image.getMat().empty() && jpegBytes == null) { frameWasConsumed = false; jpegBytes = new MatOfByte(); Imgcodecs.imencode( ".jpg", - frame.image.getMat(), + image.getMat(), jpegBytes, new MatOfInt(Imgcodecs.IMWRITE_JPEG_QUALITY, 75)); } @@ -81,7 +81,7 @@ public class SocketVideoStream implements Consumer { // Send the frame in an FPS-limited fashion var now = MathUtils.wpiNanoTime(); if (now > nextFrameSendTime) { - oldSchoolServer.accept(frame); + oldSchoolServer.accept(image); nextFrameSendTime = now + minFramePeriodNanos; } } diff --git a/photon-core/src/test/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProviderTest.java b/photon-core/src/test/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProviderTest.java deleted file mode 100644 index a62285438..000000000 --- a/photon-core/src/test/java/org/photonvision/vision/frame/provider/AcceleratedPicamFrameProviderTest.java +++ /dev/null @@ -1,52 +0,0 @@ -/* - * 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 . - */ - -package org.photonvision.vision.frame.provider; - -import java.io.IOException; -import org.junit.jupiter.api.Test; -import org.opencv.imgcodecs.Imgcodecs; -import org.photonvision.common.configuration.CameraConfiguration; -import org.photonvision.common.util.TestUtils; -import org.photonvision.raspi.PicamJNI; -import org.photonvision.vision.camera.ZeroCopyPicamSource; - -public class AcceleratedPicamFrameProviderTest { - @Test - public void testGrabFrame() throws IOException { - PicamJNI.forceLoad(); - if (!PicamJNI.isSupported()) return; - - TestUtils.loadLibraries(); - - var frameProvider = - new AcceleratedPicamFrameProvider( - new ZeroCopyPicamSource.PicamSettables(new CameraConfiguration("f", "f", "f", "f"))); - - long lastTime = System.currentTimeMillis(); - for (int i = 0; i < 10; i++) { - var frame = frameProvider.get(); - System.out.println(frame.image.getMat().get(0, 0)[0]); - - long time = System.currentTimeMillis(); - System.out.println("dt (ms): " + (time - lastTime)); - lastTime = time; - } - var mat = frameProvider.get().image.getMat(); - Imgcodecs.imwrite("out.png", mat); - } -} diff --git a/photon-core/src/test/java/org/photonvision/vision/frame/provider/FileFrameProviderTest.java b/photon-core/src/test/java/org/photonvision/vision/frame/provider/FileFrameProviderTest.java index cad06f936..05cddeb9d 100644 --- a/photon-core/src/test/java/org/photonvision/vision/frame/provider/FileFrameProviderTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/frame/provider/FileFrameProviderTest.java @@ -48,14 +48,14 @@ public class FileFrameProviderTest { Frame goodFrame = goodFrameProvider.get(); - int goodFrameCols = goodFrame.image.getMat().cols(); - int goodFrameRows = goodFrame.image.getMat().rows(); + int goodFrameCols = goodFrame.colorImage.getMat().cols(); + int goodFrameRows = goodFrame.colorImage.getMat().rows(); // 2019 Images are at 320x240 assertEquals(320, goodFrameCols); assertEquals(240, goodFrameRows); - TestUtils.showImage(goodFrame.image.getMat(), "2019"); + TestUtils.showImage(goodFrame.colorImage.getMat(), "2019"); var badFilePath = Paths.get("bad.jpg"); // this file does not exist @@ -81,14 +81,14 @@ public class FileFrameProviderTest { Frame goodFrame = goodFrameProvider.get(); - int goodFrameCols = goodFrame.image.getMat().cols(); - int goodFrameRows = goodFrame.image.getMat().rows(); + int goodFrameCols = goodFrame.colorImage.getMat().cols(); + int goodFrameRows = goodFrame.colorImage.getMat().rows(); // 2020 Images are at 640x480 assertEquals(640, goodFrameCols); assertEquals(480, goodFrameRows); - TestUtils.showImage(goodFrame.image.getMat(), "2020"); + TestUtils.showImage(goodFrame.colorImage.getMat(), "2020"); var badFilePath = Paths.get("bad.jpg"); // this file does not exist diff --git a/photon-core/src/test/java/org/photonvision/vision/frame/provider/LibcameraTest.java b/photon-core/src/test/java/org/photonvision/vision/frame/provider/LibcameraTest.java new file mode 100644 index 000000000..e72d84b03 --- /dev/null +++ b/photon-core/src/test/java/org/photonvision/vision/frame/provider/LibcameraTest.java @@ -0,0 +1,38 @@ +/* + * 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 . + */ + +package org.photonvision.vision.frame.provider; + +import org.junit.jupiter.api.Test; +// import org.photonvision.raspi.LibCameraJNI; + +public class LibcameraTest { + @Test + public void testBasic() { + // System.load("/home/pi/photon-libcamera-gl-driver/build/libphotonlibcamera.so"); + // LibCameraJNI.createCamera(1920, 1080, 60); + // try { + // Thread.sleep(1000); + // } catch (InterruptedException e) { + // } + // LibCameraJNI.startCamera(); + // try { + // Thread.sleep(5000); + // } catch (InterruptedException e) { + // } + } +} diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java index 7770d42d8..9fede51cd 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java @@ -52,6 +52,7 @@ public class AprilTagTest { TestUtils.getApriltagImagePath(TestUtils.ApriltagTestImages.kTag1_640_480, false), TestUtils.WPI2020Image.FOV, TestUtils.get2020LifeCamCoeffs(false)); + frameProvider.requestFrameThresholdType(pipeline.getThresholdType()); CVPipelineResult pipelineResult; try { @@ -65,12 +66,10 @@ public class AprilTagTest { // Draw on input var outputPipe = new OutputStreamPipeline(); outputPipe.process( - pipelineResult.inputFrame, - pipelineResult.outputFrame, - pipeline.getSettings(), - pipelineResult.targets); + pipelineResult.inputAndOutputFrame, pipeline.getSettings(), pipelineResult.targets); - TestUtils.showImage(pipelineResult.inputFrame.image.getMat(), "Pipeline output", 999999); + TestUtils.showImage( + pipelineResult.inputAndOutputFrame.colorImage.getMat(), "Pipeline output", 999999); // these numbers are not *accurate*, but they are known and expected var pose = pipelineResult.targets.get(0).getBestCameraToTarget3d(); diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java index e6886c8a0..6f54d2303 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java @@ -38,6 +38,7 @@ import org.photonvision.vision.calibration.CameraCalibrationCoefficients; import org.photonvision.vision.camera.QuirkyCamera; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameStaticProperties; +import org.photonvision.vision.frame.FrameThresholdType; import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.pipe.impl.Calibrate3dPipe; import org.photonvision.vision.pipe.impl.FindBoardCornersPipe; @@ -103,9 +104,11 @@ public class Calibrate3dPipeTest { var frame = new Frame( new CVMat(Imgcodecs.imread(file.getAbsolutePath())), + new CVMat(), + FrameThresholdType.NONE, new FrameStaticProperties(640, 480, 60, null)); var output = calibration3dPipeline.run(frame, QuirkyCamera.DefaultCamera); - // TestUtils.showImage(output.outputFrame.image.getMat()); + // TestUtils.showImage(output.inputAndOutputFrame.processedImage.getMat()); output.release(); frame.release(); } @@ -119,6 +122,8 @@ public class Calibrate3dPipeTest { var frame = new Frame( new CVMat(Imgcodecs.imread(directoryListing[0].getAbsolutePath())), + new CVMat(), + FrameThresholdType.NONE, new FrameStaticProperties(640, 480, 60, null)); calibration3dPipeline.run(frame, QuirkyCamera.DefaultCamera).release(); frame.release(); @@ -266,10 +271,13 @@ public class Calibrate3dPipeTest { var frame = new Frame( new CVMat(Imgcodecs.imread(file.getAbsolutePath())), + new CVMat(), + FrameThresholdType.NONE, new FrameStaticProperties((int) imgRes.width, (int) imgRes.height, 67, null)); var output = calibration3dPipeline.run(frame, QuirkyCamera.DefaultCamera); - // TestUtils.showImage(output.outputFrame.image.getMat(), file.getName(), 1); + // TestUtils.showImage(output.inputAndOutputFrame.processedImage.getMat(), file.getName(), + // 1); output.release(); frame.release(); } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java index ed67e2dcf..14a51b230 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java @@ -111,11 +111,13 @@ public class CirclePNPTest { TestUtils.getPowercellImagePath(TestUtils.PowercellTestImages.kPowercell_test_6, false), TestUtils.WPI2020Image.FOV, TestUtils.get2020LifeCamCoeffs(true)); + frameProvider.requestFrameThresholdType(pipeline.getThresholdType()); CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); printTestResults(pipelineResult); - TestUtils.showImage(pipelineResult.outputFrame.image.getMat(), "Pipeline output", 999999); + TestUtils.showImage( + pipelineResult.inputAndOutputFrame.colorImage.getMat(), "Pipeline output", 999999); } private static void continuouslyRunPipeline(Frame frame, ReflectivePipelineSettings settings) { diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java index 10fa3c2cb..b89618562 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java @@ -33,7 +33,8 @@ public class ColoredShapePipelineTest { pipeline.settings = settings; CVPipelineResult colouredShapePipelineResult = pipeline.run(frame, QuirkyCamera.DefaultCamera); TestUtils.showImage( - colouredShapePipelineResult.outputFrame.image.getMat(), "Pipeline output: Triangle."); + colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), + "Pipeline output: Triangle."); printTestResults(colouredShapePipelineResult); } @@ -43,7 +44,8 @@ public class ColoredShapePipelineTest { pipeline.settings = settings; CVPipelineResult colouredShapePipelineResult = pipeline.run(frame, QuirkyCamera.DefaultCamera); TestUtils.showImage( - colouredShapePipelineResult.outputFrame.image.getMat(), "Pipeline output: Quadrilateral."); + colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), + "Pipeline output: Quadrilateral."); printTestResults(colouredShapePipelineResult); } @@ -53,7 +55,8 @@ public class ColoredShapePipelineTest { pipeline.settings = settings; CVPipelineResult colouredShapePipelineResult = pipeline.run(frame, QuirkyCamera.DefaultCamera); TestUtils.showImage( - colouredShapePipelineResult.outputFrame.image.getMat(), "Pipeline output: Custom."); + colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), + "Pipeline output: Custom."); printTestResults(colouredShapePipelineResult); } @@ -64,7 +67,8 @@ public class ColoredShapePipelineTest { pipeline.settings = settings; CVPipelineResult colouredShapePipelineResult = pipeline.run(frame, QuirkyCamera.DefaultCamera); TestUtils.showImage( - colouredShapePipelineResult.outputFrame.image.getMat(), "Pipeline output: Circle."); + colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), + "Pipeline output: Circle."); printTestResults(colouredShapePipelineResult); } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java index 0a8e74268..0817cf37d 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java @@ -26,6 +26,7 @@ import org.photonvision.vision.frame.provider.FileFrameProvider; import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.opencv.ContourGroupingMode; import org.photonvision.vision.opencv.ContourIntersectionDirection; +import org.photonvision.vision.pipe.impl.HSVPipe; import org.photonvision.vision.pipeline.result.CVPipelineResult; public class ReflectivePipelineTest { @@ -45,8 +46,16 @@ public class ReflectivePipelineTest { new FileFrameProvider( TestUtils.getWPIImagePath(TestUtils.WPI2019Image.kCargoStraightDark72in_HighRes, false), TestUtils.WPI2019Image.FOV); + frameProvider.requestFrameThresholdType(pipeline.getThresholdType()); + var hsvParams = + new HSVPipe.HSVParams( + pipeline.getSettings().hsvHue, + pipeline.getSettings().hsvSaturation, + pipeline.getSettings().hsvValue, + pipeline.getSettings().hueInverted); + frameProvider.requestHsvSettings(hsvParams); - TestUtils.showImage(frameProvider.get().image.getMat(), "Pipeline input", 1); + TestUtils.showImage(frameProvider.get().colorImage.getMat(), "Pipeline input", 1); CVPipelineResult pipelineResult; @@ -56,7 +65,7 @@ public class ReflectivePipelineTest { Assertions.assertTrue(pipelineResult.hasTargets()); Assertions.assertEquals(2, pipelineResult.targets.size(), "Target count wrong!"); - TestUtils.showImage(pipelineResult.outputFrame.image.getMat(), "Pipeline output"); + TestUtils.showImage(pipelineResult.inputAndOutputFrame.colorImage.getMat(), "Pipeline output"); } @Test @@ -77,7 +86,8 @@ public class ReflectivePipelineTest { CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); printTestResults(pipelineResult); - TestUtils.showImage(pipelineResult.outputFrame.image.getMat(), "Pipeline output"); + TestUtils.showImage( + pipelineResult.inputAndOutputFrame.processedImage.getMat(), "Pipeline output"); } private static void continuouslyRunPipeline(Frame frame, ReflectivePipelineSettings settings) { diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java index dbf1df8d2..02852308b 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java @@ -34,6 +34,7 @@ import org.photonvision.vision.frame.provider.FileFrameProvider; import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.opencv.ContourGroupingMode; import org.photonvision.vision.opencv.ContourIntersectionDirection; +import org.photonvision.vision.pipe.impl.HSVPipe; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.TargetModel; import org.photonvision.vision.target.TrackedTarget; @@ -105,6 +106,15 @@ public class SolvePNPTest { TestUtils.WPI2019Image.FOV, TestUtils.get2019LifeCamCoeffs(false)); + frameProvider.requestFrameThresholdType(pipeline.getThresholdType()); + var hsvParams = + new HSVPipe.HSVParams( + pipeline.getSettings().hsvHue, + pipeline.getSettings().hsvSaturation, + pipeline.getSettings().hsvValue, + pipeline.getSettings().hueInverted); + frameProvider.requestHsvSettings(hsvParams); + CVPipelineResult pipelineResult; pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); @@ -125,7 +135,8 @@ public class SolvePNPTest { Assertions.assertEquals( 1, new Translation3d(0, 0, 1).rotateBy(pose.getRotation()).getZ(), 0.05); - TestUtils.showImage(pipelineResult.outputFrame.image.getMat(), "Pipeline output", 999999); + TestUtils.showImage( + pipelineResult.inputAndOutputFrame.colorImage.getMat(), "Pipeline output", 999999); } @Test @@ -147,16 +158,22 @@ public class SolvePNPTest { TestUtils.WPI2020Image.FOV, TestUtils.get2020LifeCamCoeffs(false)); + frameProvider.requestFrameThresholdType(pipeline.getThresholdType()); + var hsvParams = + new HSVPipe.HSVParams( + pipeline.getSettings().hsvHue, + pipeline.getSettings().hsvSaturation, + pipeline.getSettings().hsvValue, + pipeline.getSettings().hueInverted); + frameProvider.requestHsvSettings(hsvParams); + CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); printTestResults(pipelineResult); // Draw on input var outputPipe = new OutputStreamPipeline(); outputPipe.process( - pipelineResult.inputFrame, - pipelineResult.outputFrame, - pipeline.getSettings(), - pipelineResult.targets); + pipelineResult.inputAndOutputFrame, pipeline.getSettings(), pipelineResult.targets); // these numbers are not *accurate*, but they are known and expected var pose = pipelineResult.targets.get(0).getBestCameraToTarget3d(); @@ -165,7 +182,8 @@ public class SolvePNPTest { // Z rotation should be mostly facing us Assertions.assertEquals(Units.degreesToRadians(-140), pose.getRotation().getZ(), 1); - TestUtils.showImage(pipelineResult.inputFrame.image.getMat(), "Pipeline output", 999999); + TestUtils.showImage( + pipelineResult.inputAndOutputFrame.colorImage.getMat(), "Pipeline output", 999999); } private static void continuouslyRunPipeline(Frame frame, ReflectivePipelineSettings settings) { diff --git a/photon-server/src/main/java/org/photonvision/Main.java b/photon-server/src/main/java/org/photonvision/Main.java index 76aa90a71..e41031c65 100644 --- a/photon-server/src/main/java/org/photonvision/Main.java +++ b/photon-server/src/main/java/org/photonvision/Main.java @@ -37,6 +37,7 @@ import org.photonvision.common.logging.Logger; import org.photonvision.common.networking.NetworkManager; import org.photonvision.common.util.TestUtils; import org.photonvision.common.util.numbers.IntegerCouple; +import org.photonvision.raspi.LibCameraJNI; import org.photonvision.server.Server; import org.photonvision.vision.camera.FileVisionSource; import org.photonvision.vision.opencv.CVMat; @@ -293,11 +294,11 @@ public class Main { logger.error("Failed to load native libraries!", e); } - // try { - // PicamJNI.forceLoad(); - // } catch (IOException e) { - // logger.error("Failed to load Picam JNI!", e); - // } + try { + LibCameraJNI.forceLoad(); + } catch (IOException e) { + logger.error("Failed to load native libraries!", e); + } try { if (!handleArgs(args)) { diff --git a/photon-server/src/main/resources/nativelibraries/libphotonlibcamera.so b/photon-server/src/main/resources/nativelibraries/libphotonlibcamera.so new file mode 100755 index 0000000000000000000000000000000000000000..44d8bd1338e4661f6fc684af74b5cb03ba4f0a16 GIT binary patch literal 141936 zcmd?S33yaR);?a{9YR=yNCHGa=>$}W4kjT1q9UDy5Rk=~L`9vkyR(o4vYCw_3Y~xq zisPhR2HZnXhmOunR8-;`gX5si=O8Y_=PY&tDvFLMTUy2Z-cz@3_erNO>OAwz_kW&$ z>*e-&Ydh!EsZ*!w*6pm#Tr|&YGFgQBSj4l!gzt`DYJg4Q36sp~n-DfJOAN-pXNn0j z?;wB5z%T8$QEfu#cOgq?|AqtKd5@O9^B%2!{XXS1Sxjsnq22Xzl#9wuxnC64BNnX5m=0%+`$Rnyg}xt;O89$eOlkLBiR#7}o}~Y5h=<5E*L` zjpMhu_GRy$HN<@Opyo)CK5DMDX}wjvDnz`?wKc)Jt7Tr~DD%cW5vGmF5kn%yQw<`b zYOo{S^!HziGLh5d>JY*utc@-!@q%LFkHiZ;ui<)KeiPzN-2aU0e{k)=^)@d0yo2jq z`Az%hJ>33^>jPYW$MsKKAL8o9)q`t4u8(l(pHJ17&v5@7*B7|H!gUnaFpNU0aea?VexPtOE(@+fxFT@rpCRh|aNI}W8j0(4g^j{J3fCA#pP}v(a6b!|Rnf7y z$Eoj=)m^Wj?q>r#SK(9C{XE>y$2ARCBCcdyGjQpjS?c>mxL=Ix5?nT1X}HpH{c_kv zccoPBO?k0#(%B!svgeLFUa+6-TULC*&Z}m(fB9kIlcV2$Yy6zoUS4^_=8@%9S6#4g z;YWA34Jo_7{H=HERvdZGcI>ZDza9Ojmwsj1lJdd&UAIR^PTQJ!@9;aX_-LfbbH)85 zyklQEb6#A7&013Y+ZWG!;-#z2W1f5PhUq02#=Lj+$kl6eZ@HoVAFs_nyEpOt3y)qh z{@qn?+%$CW2RF>^{Pv08jrnBj=7}er?OzNnd-V8px8+>2?4^Y(4#!tFzy8v* z*Vzjf>YFB=Ej}Ci+B5mZ7ko0> z{mv^ni(kpNE_>`xrio3@&A(>bnrml9dp_L$`o1J*&(Q9>+ZGqi%6POSsqNW+p3Hys zSK0R*x_(@l`A<1ltbguTro_vRjeMYF_}q`@UD5a36VrUXc~Kv{eEgm-|6tkt=#hJ7 zc07E?$e%TK_1v!8N~pU<3=!T{15+$wtY~>uIb4+-nJC1lfmy{kfT3`ETxk66sL;6Y zg3$QChGDFQXtxcHE>ycW8}M^aZ0P)pQF*9(?nnsT?ygCp^QR68jXz<)&*hl^Lbdz2 zLH=g&8A=aFCWo%)IRkkk&kUXalPRI`s|@;akpb>B&_gNsM3DiX?D3)74F?`7f1)*X z{*{>YLg{Cnf&GM^6}lc9f}T+Ql4YRhEe7rS4D|5w@X+=D@x0LZ3D{vMel|@AjbCV> zPme)8hYjkv_x#ZH#~O^^M-AlqnStI)4D2&@TIhC*M~B8QG_b?T2K7G?8M>YijK+0h z==|3h=Mgx1h!$6*%C z`22KC=y7_Lf!&VB_zI=BFAVHqw1J*~{j<>RK7fTpsQS$Y{aa}uZyB6VsCuFd^nb0v zI9gyZj_M5X*A4vJ&XJ+{dDx)e&oQv`DCjMeTvr;*7sCwna5z46J-;yE-#amM{vihW zo3Tg=#ph9jxFTzC=={$c_{m>bLg)X$pkKxq=yR@tJq$Hy_jLoj9^)vKyj=$Rzr$d> zoMWKp=MC($&tSa#)}UV^4E)BU27WTkz}}uR;D5G3Jr^3xJKr0O-+vgi`<_9&JE3R% zKj3qzLBBsRHgx`EbYiG}oMYe*uQibOh{612HsI$w19|HV`s+&rJE=CPf1v@N(+ujr zz##v}=ZDtML*ZubF$dEq95dddy_?L33=`wrs9(+5};_5lq1 zTem^{d7puQzQCX#A2X2adV@Ij(bGcf=RJdV4;c8d8?2%0Szr(cPBPH5!=Qhc8`NKD zQ2*ryd=4>?H_~AI<{I?N>jwS!u7O;Uumy-P;1h4a&rXAJ{Z|9Iu-O~Z|BN)?XScz4 zoNs`480g_GgLq(u!93Ck{zHum6EtHTpdBGL82Fh<$Q;Vwg8h*7++vVF%m7b-9fsm_ ziov)$GCXwti3Z~?1@lp;`qvoD%Vh?7c*0=5xX!>Y-G=pYoERn&u%ApHwLLEuBaR}x z`5_65LhU9NARFO_AJ71}Q~CMJ*`)trVo$18PpwMWj`2wOBj;$iP30di$MrDL@~{Tf zYRO^@;yTKot@7)8rk`V;jTNVfEje1oYE{oo(7&udT(xV~64prjhtWNz(d{aK=NVK_ zlt{Qw%NV2ZM#aDFOs$^tRXwM{fT(^4ZNlP%VJ<)Ssr(NQ)$nA650!czCcJlOzzY~B z^eKX!6aT$MT7JFV6eU-Qk_*}7huWuh#e*8H>-lUYSNmmJJ-b!@8_(7BpGTY7_$*R* zDf|Z2)2aBMuj8`aC{cB9e?5$yqSe!`>Y?#Np9st&R8RA_8a-d>#|%9Xo*kpLi{kRL z6AW*Kyd`-W9;xt&a(`x+XjlEBx?e=femPA<=4$zMeJ+H;slTdJf6Y?$Jgwxls{R6d z^7Dw&TcpyPuICMM+@alDwS0R279sv8{%tCMgsP`d>A|b?uw7$IY&}QQk879)==yoi zs^MWzYZc^S9MUIsoW}qBAbXn!KS}Mnl-?3l{eM>DBKlFSyw3kR*cI7Nq_PtX6Ztu+ z^tMImEluICss4>r?dtl!Oxe%+HZ5bV%KtYxZ^F*i!-^NewS)tMG(NpbKYD+?G(yAC z$?_AU>|vtPk9E8z&_P`;=_iMYyvMctz0f;-K2ZJGqVzmmgN0MZEwEdqho7tZpF(}4 zx8QNH9_wPVlNM#qR#ngG7*JBr^Z*5)pDTVkpnvjL?drkKZ7TmkHLksCT+dZ_`BW`` z6+I-vN4LYSSU{`K*@T=^MmkpA~i*7yk?FY6RPovQvYWr&T^pQB&)X^fn&>}nA7 zPyFAd{EW^|x3ZrErMG6Sm^dGXO8V(k{OIHKFE9+MC)i&VqkXBLTUEPC|IdIVeYOYr z{~I9}c&%b&i^7LM-ca@*hkhr&v87Pc^Xn@A7pPG3nWo{p75;?5 zcp0Vo(V_ZLsZ*S*^tMOoO}Dq(VE?3_?Lp&o3hb2lObGH1&&cr@B^=7$pho$55_%>+ zgYAEWvd>PHU+=GxV2tV)En4|S+D&Atagm_L1=K4)DQbL8R{rN=g^yG7;GQr|Kg!(2 z%i)?_jvzZcUDf}ts^{mbo(Ghl^xmcccd2ojqWp%{qv5K1#A?VZ`%%p=x?G8ByvT>D zC{m*8UnBkDX~L_<%X)>U%D5MCf?ET;3eUA_`pjA5cC%Hx!&Uw(a3_9R zlzr;`UZwD0yWOt%j8yZ8Ue8E1FWZ#AjZ^inQhqPHMFSpI_;7YFs%H;9aL1=t{tLf* zzE*#59QD59GuW=4S9q}h4~HJ8-E8HTma6(6MhB4|nj^G!^|*1q^3U^?y@5UXxlP&I zVP$W+9v)NUJv&Ixirnk`RrLtF zy|}!x!d_GBtgf}&g?&NZVtZjxby0C?O>I$i-r|h1%8H^qXMS0cmKHk2UeMsQFDtEZ zmX+RsjMpq#m|L4tP`j$CXhA{dtinqB%F@E3ip&B^N-ZnRFL0I@RXY=BrdQTg6fQ2R zEvdx6<@rU`3lgVi$h53#XFllqOS6~c+GpkzU0+vJQ=6HYIX5Y@{y$Jl;(wx+8Ko8V zl`D!ebEiXb{RB&4f@M1kRxJ22a{P!witXImr0MqDDtiIcS6ftQud1!KmsV7jISYyw zaQ%j^F@ftdGuOEwH`$)KXh|wep`s2w*^roIUsPGJ!d_KbR$8zsGby0;|9->&R}v>C z*f9`FYpN=1iU!z9XuWc^&P|Yo3d^$V%Y$s=-!Xcvwk7|4_5WWroR|#t7Z=sS7nK#k z5oPAUqok5UfuS#}gi5c0HWE{56qGwx6xnM^oYfc!wa(%cd#=5 z6*aZh1?5%LK|y{eF{N5_IT@AZRm4GNHXB%ee}t0g6KbfWx^ksG-&ts1R##C_TMCz2 z;4CYXuIj(uYntuCUshMH(rg#<&$Q3eIV*8i6qdo)&dbk1Lb81ke7(ICT6We}RxjX! zCUQ$pcVZ}HWEs+wtg~KGc>M}Bv+v|lWPy95%T^OE9E%<|GuJAF|gFUCC8Ls&*%pl2yA-hou5`+ zTr+SMOH9zJqB#yD1nNl*n)#&BP`yC|Y~VaTL!0<#R%67Ir3Fv(37W}Kh1|$8b8Bbm zW6sc`L-$)|ki1D5l@%B>Wmh`O>WbzL2odyAKQJXJVO}+&mh`%1%ZjSg%E~GWXe6n8 z$Y zuP!YvsjVogsR?S`pJ$fj!ihMqf8&7+X+@b86pI>VNK8&ELO5AeU0PARxU%q+`7#?Y zx7Sq{oibml?AW<=n!j08T3%Xf$bRBnv1!!%HJ`;CYLN{!nz_o2IupGJ|u!T)L~4bbr{J@aue*SIrMd2 znX@=3uNwA=Nr>=yBP{C2prQ2z=2IG2MfReGf}$$r|0xQXUX3sqy0jNnS65bNBxYtW zlq-z^NoqvqEf|oZnvm1D`o65Xs9#f8RIJ3nu;&!j)Rh;77_y1e zphgl?5ndEI%Q0k^l@{xU8tk)EHJ{!uQ=T`oB>L(vH;KE_IMf#Ecr zNgBX_no*D74Ur&~tE(u*z@!x>Us>t{90rz{Tv)WsSy!fq>I-ryfTC3;;<`+Por~?T z6B@b*J8FumYZqK9Q!?xMigTvjUQt+UhF3Yov@}lyBs#RbR9h9I4 z++{@-#kD2cxL1Qd$WAkoh{t~72O=CbCNncjOG`=gKuYKt9j+y~vRu2rlKwR)c&4-9 z`nu9;R9SioEzc9F|8r}TvHY)<-!P8smD+gJ zm0SQu6AR$j?X}fTOj_87p|Cn}I!0M(fu4Ioo*jXBX6_7o_Ckz+G7=#d(L$zFM{ecx zs=8Wj*Cw|zWm#EWO-V41N{pn$;-U(Q%8UAqb-8TQ&57(TAy;~hoJ!2$WFurN)F@Mo zKd2zDD5rioc`X;Vq_c4yUA0!8eg>p94ug|>=W z`ott#pP|(o++OISGxKH0NTD1IiIp56W8(Az45M2AEF2VP=>sy=Sy-rrq1qIq*D3Xq z$f8tf$b4|;+EeBgRTQ9GLJVmdhW%AP>k8=@=FP<%PthP5Ox~5OZ~mRly`VN=EpnAf zE^Q|InAVh95A&4?r3Py|v0o^kOv^}VxHLyo|K?T7;go|}xE8KQ4ywc?ZD?pY7K9i; zFj$PD0Zax4a8hD+X+u$2T6MK^RT|AKMQP|XE%0I%j##Lm)>%i* z6`{%LClfVq0r+$DGd^BN z=E@eN0#Z=&c6{i4{Z3~tt7YKe9m?i|Et?~h;K{asSE8ZidNaRi58}?Br$Pr zxf9c=+|ofLskzYP0ys^9pbh(v@2$ zz=l^f&AUnV1@NJ`YBAFfWI*2&;#|pnw1P4`r5KQ3->2#)MPiZ`izD!`FDuL}7p0X2 zwOZWgp9xcIEAc>(=1DoNlL)iy*om)omX=`~){bO~ENc+X*-NoKzF;|R>=rD~vu9Gi z(qhD$6t5#LkW9_UDw|(Zp9c-slvI}C=^|8#fLqh^e5kz)n?h>UosTDvw0B-xP@<4( zJRZd6x}u7(1Xro(pMf(~69`>gu8j1LY*nfZn*iYBCGuhgN5N@l&%3k7&!a z8C;9kYf}p8sl|d)L@K3Ne9b`YP=%l!lPVtPIqMo0T$-~G37Pf&HC1_KJy{Nn5A&fG z7|>G;X(Vz2AE?O0By>q#b%mxgwN&sM&yNkGXdk+~jto7syc_`t1+=-fFebym%Q#k( ztC+k*1gTiYq}VUZoh7%je|l^;115?m*qP4*T8f_?*ikgZljE34}0Kvq-{ic6A zj{FY^jE#ILablwWEDVEeIYo8FWf^kWfGs{i0``}M4P?#yu=GK|Rf{}YYA!Yk3yP=+ zo_Up)6{#|^i1xj-9;v86qZZ&n+@i{2K-!p6`R&&vCP_9B7tT2)$87>aB(xornt^ojUk{d+?CEU$r7aW6?sq^_KnF|q+>@=k)ZG`+er@sXagGb z6*Wcu1j3SuV)R9{i%F9Oa%e~*<<=Gqf!e5UZHOTe>VUecOY>P_ZR__+>>U&}Xo+&+ zf!rL+u7u^H>-+l->>SuDm)WswC@vy9(F}uBkycm;*>rcTsY30z1sI;b4Bv@C<|nD$ z(xR1BmDOZY88oNiKDXMrQnE$rnujG!O$njW2`gDCMJXZ)Lrks>R2Sq^W!j)iu+Mka zl+@DhKm1#5a+R~Rdcnfd<@z>4zex%Y7tumNZ6fwnF?qo$VrQwg5>62%OHdEKEy1w| zdZ<`gsHwqDIL&#KfJl3;+SZafDwL^uQg$`%Hdhx>3H_9WtZrt2NqygCQGP4%AHqTiGAd<%IcaboM3@74JZb$J10;VkP2rb1>z($>>SB9UNo8$iMSW=vJM_^L3zHm zwRGu{1@_V!kk!uWRaaG3uK+_ozNCBvpjAZ1jm-*q)j?|%X#^pL=)HvK8V zkCsZsI!5(LmHp_-5XktWzM7w)AM7WohjTxvP+DDW<-b)h@M!XX53-rWWN4a_E|ZVNYBKZle>_vgMcRy+;jE%*jUGz=q{0{l1=4=0 zBupFUX|NtayorkGsoamR%()Uf)k}(2N@11Trw!o3QhA`J-dSBr?mwBb$<6GEM zHHS@x6zOruO)OC(9J^4LX**&%;>^{MA8o_66t9zW(zyCbZctg5qHBDl5}~1#@fUa)oWP>W?N$3j^Ev^c1Otf}x-h1Vh0ypdTUkPttL2QAJHUk+Xn8 z-{h4gcqS_uGRUENnVyb@tU(*Bss0D^0jmg^U7vUjYEy?N5z)=SiWK_;*p8!xqF!tN z2~$T=SqNvrnhKFB)u+cRfqfr;!-**f*W`3fYh!RiyEOftiQ=)1#vG*#coZs^r1R?Q zrB6bJ&<<;c79(jr5a>zy>`R{ANzn|+?_gzh%+eG2lbsnj2aLlU18T!U3nwJ!&4tVe zEahVY(lCZYWkuz5`;|$FN!U+t7GeX8{ORB37PD`Zk+9W_^0{%-1KtCh9?}tM{{$iJ5Z(6G* zfr=;xC$kexTh|5kczd8)R*^g{h0vPX!h-Y8qf9f1EG{Up*Z6BJ@Z;LD2pRmmiL8ta z`}AoEB5Tot^bC8_w8WVrW9ibg^ab|BY1608((t8AktcatVrqY~e`+c(7?d-SrS+>L zDX|}!nB0#{O5&vc+KXAJ7aakpSKs7swQA`)639IWx$sJo{Fvo0-O|^=l8#U*c(q4F zNMwlo7r#go^v&+y;7!j#VlhiUo0ZqnEi8SQ zh*0TNU&GsfK>Z`cQiYZFZbrwPCW;hYBI)6xR?)Ytor?5fVx6K_$?`*mThUILe~5Tc z(eM0W1T|;Vr+^%Iyily$atKgj+Xi`Mp7Sr@{{g;o=r8|KT9qrtsb%{IJ4> zdOuI+UtFQR-xm>t$0$4|2=7(z`C5Z;+c@=JWDuUG@Pr_|YND3k7KBHt9|)Nrgg2{t zvV-u46}~hGk5oT$d|2_T%Nw~&Yghjv5*>FaJVv#z<2x0u|E{f$>$F3)YeKd2&?R{7 zR(|x~MF__A_w|Eu{r%}+{Gj4L7%yS%ex}-_oBn$nlz%m7oge+Z%wSx9e>50RVD0jH z^xv5X&ac1M9*pbu5{&Ep9E>+Gx!z%NxfuRA!UYJ{`opo#FcL zX;bn}hO1YaWvSf^SFb=zd=JClm5BDwK8CBGu#pK~hIh042N@pE_&>~W^=i6SiuKn& zSv?U9k7V`4Fnlt@r!agb!)G!4TUNh~;q;EW{>f(eAsxhhDZ~GV;Ux@Lugc5R28Msa z^1B#5i1E3R;rm(sW`;+x{971)nB{L__&F?p!$Vp;VZyw?@phJfFRN!K!=GaKZicH@ z+-2(a2LttUd=JZ?#Q53G@^gG2%ddVaMb__SxRuotq5K|=M;@nH4e(~xE|1iHoAa96u@G|Fkn4KQZC|>}0srj|$Pr@W~9{!*KPgyiDE4@Hs5Mm*Hlnhl311&hj5- z_=gPdW%xpd3uY&;GCYFeUot$B;du;?VR$U#)5`Flv;0#SejURT7+%QmSqz`e>bEhx zlI5Sz@M?xmWsO0Hsf3ggqo@V~QqHZpt^%iqlKM_B$X z4ByW17KW>zLXfH38Q#wFw=?`nhVNwf4u*F!{8@(YX83aq-^1`17`~6;FEQN9@GgdL zSHIIw<9!RmMT_Qt%I&L*p2Xw3_qO!^=W4KpLG!TEes#U@D_&izX`IP;n6IA zJHzo4g8t7=hU2G-{GU#S<0o$XpWO`Cf0Kj~_b?nkrQ-kWV>o`&$N%v%e7qkO;vmB( zF#IsX>F=QEpI(NarGs?e8nBRiTQ6ZWcegVU`Fg$_bEeyx@hX1pj;YofJ>jH*PXZTKrCo{a0;rie7 zq2%2R|DNUF!|)V_?_>B3hI<)4li>#$K8xXp8J^1UUWQ-DaM2pD|BDzN!SIV29?9_8 z43A;>B@DMRoX2BR7;a;3}43Z?F=tw zcss+-=l0L=5|+P{;is|uyBS`}^6z2za)$3?_zH%58D7TlgA6Zc_+f@uFua%HRSXvo z2kifPhDR{GhT)M6uVr`)!|NDsWq3Wqr!aga!xI?Z!0=fNzk%U4hTq8W`3%2_;n@uT zfZX62li?d#{@o0}h2eV`ek;TGF?+Cr@sfOf0i6@N9k(KhNrE zVEBs+cQO2BhHqqeC&QZ={tCmlFg%U%b8_{|o|6{g{?H=sI=T9l?VT3;`>dEajC4FF z+H?B%S-!}gIc}?Y;`-#`Hap1-NfiCLANsc8qi&gz7BK`qw_(VErIrzfsSMJa?t6F zt^l3S=xWeSjIIaW%IF(FcQJYm=pIHlfi{N)+TQ>=j?uS*PG|J(pz|4h2k0h7{|0m` zqwfXX#pnk?_b|E@w0TgV{YOE^F}e+OI-`FNI-k)`f^K5;GoV`;{T%2nM!y8QhtXZ2 z&EbLeUjrS-=r=&8Gx{yi`HbERx{1;6gKlN?2cWwc{ZG(6jP3z#9vo=@W6*Jo{tR?F zqyGgupV41~ZesLt(5;OA26PvrzX#pJXmc9cj|j9M4mys}LqVrAdIacvMvnsB#ON`g zTNynLbQhz~0^P&tIMC)Hf%eY<9mnW+(CLhx20EY7NuZk;Jp*(rqb~&A#pp{w_b@sg zw0UTt{du6{7=0<|bVe@$ozLhT&`pfK5_Bu0uL0e~=<7iDFghQ!d03$RWuW62y&QBp zqboq?GrAgd6Qk=vxBBTlr{4g&i_vR9_b|E%w0XGR{+`n}fR1DIt)SBxeLLuUM&ALt ziP66S-OA{DL3c6wLC`&nZUt>VEztg>pyL?b20ES5zXzSq=qEupG5Q(Mt&DySbQhyv z0^P&tF3{!?f%abm9mnW5K&LbMEztRl-V3^k(eHz9W%LK2yBPgX&^?Uq0c{=`X#Zo- zag6>9bULH|1v;P6UxRL9^l{LwjQ$367o)!i-NR^eI@*s6v>y&Sj?qIwr!#s4=zKp{0N`UcQlj9vq}htW--&C!AOH-L^~^sS)N8GSqGd`8~^ zx{1-h0o}^zdqH@Rz`mVx{J}@gYIFpIRov-1lkV=9mnXQpwk&W0(3s3 zM}cl)^cc{sj2;KNi_vF+?qPHsX!99?_Rj$w$LM&_>5QHRI-k)=pqm&y19U5+F9hAi z=u1HNFghKyd0e3Vd7$GMeJSX4MlS)KuhA!0za-aRM}`R>&Y|t8X&vvbi4$(GC8{m8 zuWxfV?l^kgeq@-L}vv=bAjke{I*9ZWs7}=zHOrc%uoI8J7iD7_LFM!f_486@hCAuA#Vw z;TrBa_I=-G7ur68yA$NGpZtXj1!y7lnewTJ9_5^l7kL~H+EMLAXYxb87r7uU*wW&6fNTI$E zWm!HK%1EBFGkm9??AyE#`nC#Jj-zROD%mLY6X*Z$kVlt=?s3_+4ts>S-ewkg_>(<* z!dw}tI9cS*KRB-=JxrXQe=xiQf9ok(w@Y(`&DT9r_$5z(06s55t8sqwPJ& zU$8UFS7SE2*SoTOR}2@PqZX6q<}EN_!2^ z!Bb6U_l_nL`rMRCZP%oWx9>-r51FG5HTL!8J(XnhO*e@h(cs;cljZ9S7f(Be+B$F+ z^>XJ>(J?VhTyG5%c~8aJe9xLq?&IM$-&*sSLoSoZt2NtvJIusSblaP-OU>s*x0!~y z_FjfIK13Vc-}mJ`gRCi3p`)k`fzQvft zSfsM1lUmuY(Em=fMf}G?4PpX?tkEn23%gtUp$|Gns;@j&AGWsJ;*g8l*A0jXMaYwSZ?c>7%8rIMrq@c%Ea!@ z^2MV39=$B~PlC&qqAZPLnSZI4|5ZKz-hugl!P^=k@@P!vkD8k*99cftP)F+!ksK%G zhmEcisZXf7&IZ5x*9rFl%OKeApm^f_Qr`BvTHB8xKkD2;c{#66h>D8nxqCV>>DBZDW?t8zoK> zPv;`d_F135-*uf+d!0yIsI}KD%gxu?8V9`dSl5Te{>~9s?(tSVqZ5oThIyV*bPKs8SHow3x!xzz5k8XPhtL2|7JOSb@(^|eZEQq2 znGRg{7i5nn*d_T4;*nwynrCRvX^IO=y$EGoW|4B|m2*97&7%*sz~BBR-{hw9ntzLK z8%6xUFLvU3Oy=*MNxt)C<#%=8s@o~a@CA7G%iyrM;V(nVFc`d2{%)QhGCvLaDD=za z%U1FYMVW7qHqjcEO0sl)r_I|I%+LEV|KrU`_aw+Y8Gf1O!te=;JX0pyJm*Xhp0nZC zBPI{`gqLBSi!pfyMV{u#z6NY=jB2M$jIW!+T7Qu=4n?l{CSwTtQPY$^>M6il)IqIn?4m5+*%8uEtO)6YVdwHcy^(#zO}=~FK8n-eqjEALh5OhpGju%$x*iQobQ~-&yL(0s^Xy0dRb<=OYB5%K0b(q~!ZE}T z>Uk1%ccYF5v@>ynsD33zEp<1hZ4%1QLs^o&+hTD~L|?&w z=1Cod3HM(qP05mnyt+S_HG%TSw7p6E%PS_Xf*dgUmu`1;yJ1<6k zV+(DbsO{pD*|3B92=xdK<%q?*#lCr8y9j+AKETLG&B>(Y{{j z7a%7BYN`cDCH&xpweKa2w zga2<)&wbzZ$#PNX4_O|uE%5+Hx0(3p{)Pv)pY#~47w@i&R4aUwcLiiwXK~Zm@b^It#rncs zkFvUtKT(hYUo+S9ZA~WPl07mmX-UU=5wboVm$tJPeb@_qQ2$R9qaPD7wr^Z#h`g6C z5nt^dgL}C6sxeyRy<)}~g6`1gsmJWXH?bsTmKW`NR|p^3!bA~s$bo!h2ZVLkU|nUW zaY6Iw*tVWZVBqyb@J3^LIOYQfjS1@@_g?f7+3Nx5mi$QE=UKi?_!0AZ-H*HiKVrJi z20vo`xNpZ8*lDNoBM#WY`{>{LkNS2HMt-Cz;+1>Tn@#W|=0jT#^yQJiq4h>5<4|W$Ump4OxREvwjT!O zHn2jzB~rGSwmP$T+Q<&O4}sUgi#*=JBRqES*@$r|FuvFSOx$%b%D03I_g2{t!gmb5 zyqo$J{TqhgW)ktN)`c~o{}<_Bq5NT7U*eK>YzuQo;ycYjKW2>n z3VFR5G*{VD(Lc%b-2#0~L~KKAdGZnYXx{;u$yW~W16e35U{}}!@Zx)YmzjKVDt-UZ zEDk}3c@C`MZKx|8ZEeB&ygm-~TgDuUr8InR#JW2c^A_bPC4S&L6Z-pu_yhXii@ks z=8%7p%1^#1){AH0{qm3T$I;6)o02~C7~<$>kneYBQ|cal`6TEMKokFjkxz;h<~P%i zkk2-^O#|PXk$zmIAD450oG(V5ka`#+=YYxhejL93IOL=8wFT|co%S)#MA|D#&a*h* zj&S$a&|yH%0N=BeoTGStZ@BwogZ$?sKkZ4pf$M$j&rsXb(e5un{}p5CuafVvZKOXM z%f#0S)cro}eFO54?0ay33D>U_U4VOcCHAe5hQ5JZrnWUGLw#>WJyd2B@{r#{T70L9 zZHeaJiMB-Be1kAw7h>m!>Nm*|}O|X%ddo|t&GhuFhp3`Bjz0We5)_T+ra{r|h`!BQ)j{4_dUT|UFpfoG^ zPrIM|Jz`GSw^`Uy?c2rm7?XKq-xGznzQ+8}y`&$$2N{JJAs92E{mnt`>+3kucMrz7 z9s2|>>`&Ser{Sf?Jo|8Q{Z_OqAg=@cVZ#352J{E~RSsX1f}duw2QjZ%VBGglvr^d* zcrtL>k6ecOnnu_>X6!lAn5VoZ#2TNde%AF%I*0r+mdwDNbhDP`7s(&i>#&6kVATF( z^!Hj3cF2jn!gT4!T{*F^2l5l0m}{-V+=jAWc`a5t+BZswhsFi>cNp5(FT`P5_Y}O4 zBPU!x}+SXx9nBT_u+Wsi&C7sjWrNc6C@6rXCxPF~-PU^ppn2b3lcpuRT z+4Q`6`B=rnBujph`r3wtbM<7p1=#vb&esQc)-HeWQ>Xtaj(Mhsj-b|OxpG}qvPx`aJRUCRAh z#G5Bq|53)7P2uUD^_X`i!9Tc!Ws?)Wp|PZ(Hx9mm)>NcF@)1;y%8;+nb*ryuC^k5b z*dVwc8W9`md8r=i1FDDmfnr|0zDC)v*fW(jI_G^UANn;o)`;~Dj5S_Gf6;mY_CBf( z{r5-EjjDgI2mPE%w?e1opdX`j6(^K}{tUF<|3#qpQhw-}`Wm{BzIP&YPk!V~d5>;` zf0KJbG$!@u4YUtL`vp;02a!Ecyh(O4MtpzAw|M4YwM4xszRS3Cq8M{X3>A6sSzpn- zc#(*D(-i&Cz288`Rv{ki3Kw}U^lc3GKF7d+MdPv|)^jbtsMl^0KH485pR_ejyzPLT zu_!;sYWgb7mG=$xf9!V|?^sZV=6>sUY43>7Z+wUNbS&S0v1|FZiwj_H6ES}2`N5># zwRb?q8O|FDdK+(;)Y~vgxVM;NHoa^{T#d08XBqvbww@T>7Gp7QdgNH&=BJ<&?O6cE zA=;h`oyfHdo`W3C7oOuo1@_R@a{<}MuSq*Q{^dMCe!aC?2X&W(Z?Wlw7k@gHI%?g~_hOXS{XrHk0GVdAjPVnE0 zd{#V%X+=3IqphjOwv9rbyU@Q6rHijj7`qNL_Lt1PGdW+rN%Y)Bv+ZMdy==E9@?Ykb3EAy*&ckt zUb2ss=_Yp__S$Itt}>h4G+tNt2)A>nm}){FuMWq2J{VVoYwy|-!Z#7mBiD|@UR=C* zaUz~8u8qSLFMNG?=G}+%wHIQX;`__^9*c67;3s)7VpPadkG#U>+Iv^Hc>AvJ)86@D zMD(U&q>JGZOH3ld-M!r8DM&ZFPe9i#8-ypnDa`G}S=8rHR~?=qb>5KN`^`F&+cCy9 z`=Di9o0ZyMGsLqN&)U~wPh#zw;hwd7u^;#SuRMJii)+`6^t`+VX=_G#?8sx6c}9EI zK8byd8@2rmYTr9}p2rbB66>)nPfNJT<4EtEt5%_jRhxq7$kCpjPDnXe1a z9nFvr<0{92xg;Iqv>JUy-zTm$c}z%KYtdqqSftIA{S)0*j{eE7(0ncV6pH`zrO!qD zk35bz*!0Q19Vzg~Gq893G{(crcz(GX{x24FQaaT)iS!3P{s|k8K)ZhfO}w2{?O1^E z{9}PrpUpwv>`{5Y#+~Z;AJjp6pcKcRCd-d*bM^H-y&HJv23xNQeK#05wWZm6N5A-h z>?!Kq#qxPG?fsJLJ!BDGP&P@4(NF<<b-6vPS5U@w(=PABE7KJ^OIijNuzJ=_A+A$%23wX&-r}c)(ZNgqsdZc(; zUwie;v311F6+2Ba!bkkps&bo9PVyK<{igZs?jyo|&k?M}F)kiLI_0N6(95g=M!Kzn zZcna$#?NE-xxzOVdPm;)-;o`~h~%D0ChX})#Z#Zh!k+F#nI$NXF&&TCHign&1HC|D z4m_VCtf#=_j;(U%tVMq85p{S+VBZC}=Cj_AK8yP8n8oZqoa+37dbMR=$@niV?LkNB+ zDSpWxa(=%<`_wN2K91rAo!`7+8o$CE;P-UYo2>YKi}Ab7fZtE4EyNg~piC3|0=1hK zv=3^-xe&@@6WTr~t-px=;1p%7*tg_mXdkJkMzfJd^f&3~IOas^Ljj$2+g%+;cTxHn z*}q5EhI{&UnNo{L20NYUh>G7ooz~IV&m!G{eh}@GT~OcL35?=*+HVmR`*WFy_MBifg6!KZaEgs(*0y%zZb{W;d(pIcGp&q#X{7xe*^r`Wa=&qMUG zRY;4&a}!GMg`C7sCHP5GV>#9~+MNM9P=AzMXHeWm^3yZyU!omZKlHi}c}d4TidVvE z{ZH$6l4B3j5qp7;XibKTG#O~TK`(9VQ5W&1?eQ+$RdPds!Ve?Go1M4k9ix)k&e z*2hut=K`AtjQoQ)T=NA@z|s`v8m;^T{7M?^rI>hHhj#up{EvfwbcpCalF_ zL$IlU4Gr@2tuv**OFUktZ0J1AhNwS|!QQB^!tkBh&K_wywlVIPfa|vN4(S$p?uNbj zZ3q2BwsRQy(6@WKaZ&&1@%SjnLv0*KnSp+5u&2*rPW>Htqk46}l@6QP6|VWMaB7q4 z9hN2i7Wp6QyI?<18>RUH+t7d?7>Rn5ke}rHGs&;~)>hOR;5Fd4X#5ke)E}qfw=o32 z>lD8qpgqnn`JYhy?l^6r-`f9G-{x?|ZwuqM&Vb+NNjDfP9VpYJ`K>)a&Toy5Zzeur zhqueSHrHr-C9li*hU(pRih9Md{=V&DjH4gw=jkEzW*MyY^KHZj>t`3}PqLt zp|_o=oBBD2>Frzty_GAytvH2zq5SFRMM8~H`)Q`NYLM_%$H zG=GvjC!nVuHHL^LpVmS?82NQyb*3ycwhazzvlnBPe4H2aPdEG>jkVE8Kcsxves!nw zF;pMjY43raQJh@;JLa>reVt>Luy|TWV!?g*1pJt=OpxnG?Bm4yEEaiY#Pr>V5l$gy zW`JkMIXFX$JOcYKIzAh?YqG*!8g7aeGh{yOx3)x^b|B{5vzlTy#8c464tkD#C;F-7 z4>;EmZ}a7+^nZ?xc=`d5r!6;M5C*w^WA5SuM zc+bN%4*qvAu-{}%{bZ!6BYdRI_t98WhvQb8@0*FH4&S+^j!wiE-=H72qmS_nIey}B z+x2N9McxhHiXA8Ro7`5!eRMu&3eum2J}Hka7IVsKTSv>|?wq~Q%@YdmJR9eqI@jaO z*UdSUHVkFjR9Z`nmKLkh$p3FsX|4;AhIJ~=hO|*Rih1r=Y2HhahBYmv5#N+{6Ut&g zNb=e^4QFrWqK~nri$Pyve=7cM@N}ChZ=FwbT1@=au#ebv0>>R5;GkUieE zNTlFw!1cCV^#7LT95?VAagkr{TpEy-#z(!vz1N8pXP2!5$B%NJKHRstO5vhNq#y>_ z6YHS&3u5A%P=$W>wP`s4AT2y%g?mA z>mMl3b@?{vkh*+Z(`9E=K$jnX*|&KJ@{=yNF|4VB+8|RJ zw^29Aw}Q!MGmvis@Kg0eTnIjQDLz*R@mXoa=WdNp%q@PKUJpKhtN2V~e2y{T^XJ4T z#t-=xGoFLSww&Q^Y0L8Epv|qgTh%%he}Q6C6xP+bFNhrutg8jq_D-y;DQ_{_ycKQH zo&%nliNh;= z>1W3;px-E-=)~EimZ9SE7(7R#cPgel-|xKk3p78Rfp%aI?fRTe_8!U}-rcI%LkqKq zMX0w@>3Im#^FL8X57nvOYth&3lYhV-I{WcCP8;)z&ohGfJk5a5D<_aw)fHAOvrtzv3mvb1Z*l=_SJsWMf<`uKXaRE1s%$!j^3*E70z$?=geon zz*#udO+Ka;cfGF`fX7fa^=sfXUdSIA^^Z5m=dS*N@p4uO*(N1vvaJk~ZH0kscWoRf zn+vjSQ?kuwvW+s3jrxaVyYdvWIfC|s|L_B{eF7eW`)!?)4Rce!eoF?e`&`-|cVR!D z;*Od%n$LBN3i#XwsJBeX7S3e*8|nzvZ?Q_YiT^>_+C#`@nXdI4`6q6ZC&6PV*`n%H zOl1woHVXBoDB1pk@48JsY#`fbz)i!kr@Gyp^H=2W!A0v#??gOb8ezjv3%hcD0qpO% zFfQU9wC^D{=H!8<{DiquMM@X)QC=6WW1shJ-lNjIb3_V_=RfOt=h6Nz&Q~Dcc(nbR zj<@$EpK1&jB45B3qU0FfmZItFMaawb^@M@G?yOY$stD-oHSqc=>ZUQg4tHH&OAYk( zAaI%|??)T?S`0M6$9g~S9|O_3&{N6wvwpH^{wYJ*!iFH(ZZME7cey5;7co7>*EAM? z4cVSlvMpk=#Tv*)@woF1%@*!P|Ky^KZH6o7G~l`|2;l#VdRu@G1}>}{bKVB+1#JPX z+X42v<7b(SYwgBrT{VDsRI@5>0H?9Cz7s`lPuAIY2r@Eg5?Ew8b z(bx-Fg7Tf94^o}4**dH*H0F?h7pZu66?d8o1?-vpu>;sY6-Ik4gwyySJAD=Sx%f`D zZaYicuaR?L=XmUYkCm^z5m+Z|Vg}OrI4}dZUhK+A08aM*4cfa2n6%Rb%}zz6t>Xof z0r}2BKC*df-@vayUb64uz$^7~Q<;4W>}4ZgHqv5|&y0Mo*{+;uY7gV99=I2DBxrqn z-GsKRm$-6<0ka}cIr5Nxi6<-eUY&1g8mNvrt{k%0z_^NzzYhB71bz_soy3pLmGcq4AH{DN zoXQ^FMY&+R-39+ZF`)Fnh;8+CMJ&~))^Gh{i8;#0jtSVq4AgryWFmVwg73QB?nWJ< z>|q3WJ{6yB{rJ@EcAc_Y3+m+K>x8CD|Fb|n<~fq0_+&B9aMXK&;`4RJ=Ys}(9soX) z+JkTDM!Ar_B~kMkk?x$$hlw1N#ljf`J$1WKhxxF!Py7hkL>*n z`bFK;AHQaDQv49AKiZUxocBcKE4LZQZNeTu<)>%or|Qd@A!N)@F-vohjO&eLoTSN! zGsAuv?}3ajC>gJ0GM;B3;?V z9k7GuZd?>2>FfO|(9x;*d^H508SsNv$7;}s!vG6{1C>E!oRAG5Jm z(4llP9nalq|C;-nXQ7i1P&fISTBef)20Ed5JlIcqz&l|Ze?WHfHIIdmozAmT`38gX zX*hFBy1EGY?n9n?RUKsp`E^}?3|~P0Gnikm@)2DBB_XhhXm2gbuL)7dddv;P?@Ck^ zjw>5ia6T9KroAEZ8&%4t{O296(#|GGe}?{;jJ~G4bl%|zUHGn_QQ+sWK1Uiov!`^i zPPk`Ky(k~8%F}yfl=hLj>*pQ175$;Q|3lsBS>RuBy^rfXT<_v~2N%5`L-o-2zu?l( zdG7c|d)Gb;?NS~(FHQE`3EQS|;Kln3^xXX**6ib<6B=hW8ZV&b87b>H_Y=U$Z;@VZ zCB4yeRy@b`pOI3!`7OzYcb>Z^v9v5rZ!Jg*<(IoqAMyPN`07#h674@Xg1Yr{BfmaH z{TnF_{F&uFs*UDPsz>h=AL=KX-p{1_Ex6yTzSA=d`t6=ZTsTucb}cTy{_wjvv=6xh z`l37yxTrk+9uD1C;$DM`)>TB)ce-DXd%5~vf%|gxeTBN0;$DQSP|@_=slL;^dY$@C z&u~3xn{4KnkjZaL8N$6y;f=tlPZxqtL*G&RvDO&(M9=}92i_qmLVkWG@M%>~CGd&r ze05(&*xM&pn>;7c&XHWR2j^YdoA4WiRJW}YzwdD^-lZxC!~0aGHs6Xt_>F{ckA8lp zocO`-o4Al4&ju?uz6Js&Gc?4x!LDTyltB@bh z@7}cIeXrq{h`g%{#nbf_!nY6aS-qbl+&e!Io-3it_j|1LjuK)C{KlGhg8Le@i}#G; z>HP@8C@t1D$(@R`I>!nu?hL%YlsbR+*S*ut?yEO^{PmKM`KP-x!bC?_sI-<;cLv_| zw+&2dkL@(MGlrvnq#eJ`<{_D__|20K&0`M<{C-3i#xlL9M0;;Nn?%P|7z-aC)b{pC zkKMo4)^R2pBMP^riIlib?F}?(U7)4u=XV~_Wi5aX;NM6;0y=z1$E$$fr|nT-p zh%-m@uHZVHlj%Ww4%p({VWz38@tYg_@!J`ze{H%?G_01t_am^MfZtf`cu1I6I93ME z*$|eA^4n0R;4agBYb_Re&ZY@xCLFE8T{sT!j6$ae77E`V&^G;sPHa2gQ$t(%M{at@ zg!;Rmzzxz|l_=a}%0I-PgA8hElQ=eG3U1u4w4-DWoH2iMQCo~;;K>Ky*)pU4r zHN6{~fjMn1-WSfqe1`Y#@V?%W+;qHq66Wr-*xx7reqtN_h8TYDBPiL*-b{Ms0Lj?uhs1lA%y=Bxp{x==_?C>OtA=O^fCEwOY_L_mW@W?}zB; z*Jv%*sNQF}1u{Pl8Oi_5!(Cr@hPHKHqOHI9*#a#-c3gK-c|f(4lmn{G|3=wUeFGiATMQ!58WN6MWZo{{rd= zrF%1UZ^Yw6A$Z&$sqxs0HaL%;lP*HphdP5`WoIQ!sCTmB@g>INod!HoJYd9QeFz>W zDLwurh{s(9JSOXBFi#KI@V<}mTVbf1^msSpak&AH?ZC-~e~&hdY#6_Z)9>8Oi-@sl zt~x%6#x%}k294?CefWL5NtVVU;^SZ&`=fs3m`1to0&Prh^6O)v9Mfw< z=wmdVY2W>z*wI3J5zxn0HKy-^KAu(jxLoQZTE3%pj)6YPls=Z9LLaWr`s*Vb`rtk; zc+7kY9s*-V^KJWMG<(eR%cl9O`5|PZ_wS;0dz=vH>tCQ=my&H9>+3I3N2oEAqGX$X z3fa70^p}m+T}C$i$9{5YzF?cO;j@C|8f73?vRj??VSe~r)O)Ft>j1v%zM#WEE{X?q zANCjcF0#pQP~OO%z4#pu%0uz53Gckp-T}=`U!Y8@fgf*?dKv96L+emJ2J}AHZGR2v zhS`2P=A>QGTA%+F?Pxwov*$NK2m2st&p3ZV_Uyp9VBMa*2k;x;$WP<@0jV3!o~sRX zvlIBKY%`De44!upQ_>#b@BDmfwz)L~pJbbNt<(BYj1Ji5GvM=oQ8)2fBl*y zWt+DHKb1b?iO(Q?P8zN8xz5k0rq7ij_#}P4*P!Xsiv4h1pSOX}KPWyINIo@vlKqC_ zvk*AhPCnXbGO!iv{{Hrb-)TRke>egjg8N_>;&SSPMSj_|KCp$5jrt%NXI@;e6_QPl zXRbiK4NA6AQZ}s*XnqYP+s~wIqub6ydaHqKUU_aYFb=N$fpPEx$rjXa+f=`e_RFUA z+mH~l$$ncgu;0!?y=h9ezu`NrYiM7t-9R>qXQ|(gqKr|$*@FD~k{{@|n@P5yv11vp z_1izu4v#bTf({LH(Ga`mxL}n>PL&A!MU|e0Qmu$5<>@ z2idkL*^;DeT0agpkZrM)ZFJj0wDF(nx4(mj;C{;(quFSRUp8(0O${L%_1owiH4m}4 z>JrrJRI+`G@A~-LgF3np=LN5o#;AUaM*4rM-yR{^g8FTp>bLK~8y|mPgAVolDpx2FYni#v%$zxM&Y3f3=AL_|kG8!AT>8>qDASkR z8hiA&9CT9b(P_%`#gE>6v770!w>N%_G-UlV>Ivn?4|wj4AJsX=`#fLBez{{8Sq}xb z^if|3KR(w7KX#b>c=9IvFxu8-f5gv}wR#zki~1OQ_!bbG)wR!l>&Nu#TYBNgF_RxF z4St-q=Bf|(!H+Z920vV!d*L>=);shs0GIVYdB3xP zvikbpykLP%-<#95He&gZ)|$xwB5$aEkEUNaZZYIJs|Wql`=I}=sRsRizJIsqzaP9+ zCjC(%^tXcJ1!(U{zxd ziBU$oBf*Uxcgn2;`g_&m38o%nv#fRx25+X>?mrN><`vKO(e8f$znClEU5;$JoBTfc z_I0MK{f(wKc09(J`@)ykz}XvLk~zy-)`OmfFY5*v>&8#<%^m!08N=SiC&0HZ z@)+mOJ9Z3TmE7hn;+yFuquZ8(_h$WkaWDKiX7a}mEus8r>4QI$&HXd-ZIH#E-?j#~ zUjw)F^RI;P=Zk&thjXrPI=8s9H#%AW6u)*`4?4fz2c18;#gt=+{_cj(7fd=I3ZXN- z4>}(OE^?CbxK}xG_PEIDh^fCz`^eX7%2VD?-b_A0==(^&bsFt{phvss_0{enM!N%i z17pd@3tq7wBA-zq?S2a!z4hB{v)$4*Yp%PQ`Eeong&*mJz461#-8WK3-YrYM(DK(Q zf4^Bi6#g^dH{;3Ay744VUkiF7+2Bbm_(FA7#@}B1H0PVkUX#GUE}o18?@W^?uM)TV z^bf$%8&7TkzZspiz0m0}>HG)vgwpvJo_nQ}vxkIE7vDx(vU@WS+#YYz`NI%8H}pa0 z?|=*MPf(^;8ATd0dfb%JFZ;;1&fFs;`ypD%(^H;uuK1sOfwv&fmw}(Iif z7kDE0egpj1{C>snI6v_pq`w~JC-rY3?6pn2cNU%cIyinxp6B?r@cRkBAM^VWzh-_i zKKy{+_xT;**RxGiDBlw%W0TBDq+cefp~hJpj~aU{W}7&^1kWXpzBh&NZOX`*aC$k; zHPG!D^jDktWQ=b?mRC*O|1d+@n<9O53TerV*-}2aF}kiF&s{p%wXZ<>lk9hqGO3|u zoY8e1=*?TCh3-4pP9E96@;*PEHs)or-zLC$vaO4aHVvUoC(U#@cS-Ua?TBmoD&+;I zJj;D%az>!U<(oGNpC^>I|3;qq30-!|$T{5s-eta3Y-is~Y}3C}hpgE+WjyBj3j9#) zdwC1E%m>6LJ|(<`zE;+XJNLbqH2wpeeeH?4NLm-KxVOSQw_P)N|4pF{dNvb2ZN_D9 z%2WKFzDkU`(vQN+8^_qo6zBxG}q1Pxg}p6qSgui6cA$xD6&btXY z<8bJM{Qixf$ZRWl(ZAD@p3J#{WjuRGljpn4a0a18x9qo(v}uHM_{}z-ClluJ%jH*L z!iou{jx|OdojN|BXRF*;@=WFTS$>)P1h!L67`H zLKVKW-vCvRvgX7NIqUUx&b)EQsKMTjd(K?qJo?=#;wpRj3Ry5P0m#1oBr3_D*HG*|Hren3(D?ns@fRkTd-lt?DoGypR~8=%lmgc z5w1S_IyAdGO3&n+iX8D4^(C)LS~!mTme$YlX04mED9bh{Gpn9&lI?R+vW}>TrE{oX z+CPVL&Z=KfgR4iWA+btj%U+t!^8iM4onLqq8mb>pT38gW1}9VhhQxm!TEQ|(_anFH1o*V_4W`o zxW;^zy?k#+tHA~4^EsY{w}w9be1Di~`U9(wF?K1J@1=e4=~?y@$(dPl&TIgFdB(Aag#9Hpr*RI4oZBG# zo$Q>$;rlx0<8v0SXSi|Bv~~XR%1G{w(Ks8Hv-D)I)faenbFQ}H{OvDrCUTJbHbnmd zZ+_{_ChC00o^Vq3%M?-9E1bjY(pURzO9kkE7pKc2{M7~3{uJh}C5jkxl(`;qmRBa!+=^cmG^q#}f^sar_$=#gS zi!2I!yzBl+WZUy=;om=?Rkf`>Bk}db{Sj@?i;hUWo^bV}JoaK|LL=t_HSItzUuNDW z`Wiqc(l2BmRsCPN8_S{II6mCg?oTq#8-LE8u*vHfwn^{@!Oy-0Xc*d518zC?a-*14rk8`WVhtv1|QBM2;JA2gFBleQmW2sksHic{hc9kv9 z&*^mV{4h3J;^>9UOqw?0)=7@iksUclRMf;kVp_VbgNjW^yNqpLUDx?k4>T zc%91V>wdj2%AI{fCoF+3(a##auFTH5j5~#o8@h+y2=2?+2HD3cGW{hylsS=wa~<|` z8sn_=Rgs~*qt@FWh^fmp+itYK+kGArvPknO>u%9s>GkP;)G>Yho4_3ntY;bL$jZKq zw>iT;=&)tK1iu6L55`^%&XeVw;L+FwS*y7f+Whhz;DB6x|3wndVkd>C-S$-ReT=+= zR3Y#3Gr{`>Xj1r!ZxEL=Xl2g)YjEJ-H{+)?hpv@Iq1W=N8zY9-8&%=Jpv~6;ah3-4xgNi+qaaH=kGU#80 zZ4vs#w)_-(BlkYMhA+4T+wd-ZN%lw&L!Kft(W51DHwNQL3-`gSL??m|Pt7W2?0t5K zYkxhyQ<4LJ0$sE8Y9n#(?`~-%Z8v=_fW5rPIK~}#P3;$g+e=N|I?-aH(HL$8EVijI{sVzJT=4SB*0&(TWrcy#?RMQ zsyBqzS2*J;!0%yryLu6Kh0y-d5vp!jm}+7F+H*;c5m#O06FY5%4KKA2`49>1@xfFqgm>V+7w;$)jA^jo1rmx2)kh^)Zrr zOu=u&W9mG_g1Q8)OYF}Ho~PooN&k%opVTG(h3px=8#?weZ`=#Nj=)O|`}|$T%y4)lb;-B# zm(ZgP^x0=3&phR>kKM8E@uD{F;%IRK^C-qxo*jgHKMX$Ch>j+y$g98$#83PX{4MvX z{g%F2ch@#jpOk%;I=}k(=r(x9om{HriO0va{SDglI)cxM4U_og_k+)guOf8sj&`)k zdV#D1+Wfu9flH71}3v`zZwQJrV8O+!O?Cg%_2%>N4e#T9qKuhZ{$k~0)%a;KFO zo6LQdk5E7NlzwFaJbVQEQXu2KqKt%2Gn6y<#U|-m3oso8+#YeUG}MK zt>!W`g|5YjeG^^$Cvf4j6In<-mVEu9GY50!K1BUKU#YK1)uj`)3ZuobGpf!L!rJ(9D_I zEpEm?xgVv_oS!?LgX+Xj`w%=*&Z1utmv#&7Hp;F;2PA#8%YI1be@MFElsweaB6ua= zMR1O;?3W#ySK4IZ+e2PCFG=z`=h%M{nos(W)Njf13^aIY^HJ!(@)`TGew0hq%OVSB zLY?#I=utL)zd&Y^PjHT(Z~sMVf&CX(KI2|y+_`4lr`~J*dEM)`{hP zzDc`wo4gag&7jVk$x+8OGOu0QC+!z`2F$j#=5n4kdT^2Xs&YN~lB@c=Z^~T}E=}#| z%KwATvwbbuZ|TPwvH0uf7)w2T>(k0PQDSETDU3%cwrnrF{W0?NNAk^(J2zYCYX!by zv{o0umv{%CLB?%a2Rn<-6p?3rkaKBr1&&Su|0nQOtWUjj%nnR^)r6*h026%PBF2qP z+_}pcDy^J*t2Fkhr{rYg7fX+y9SrZ}d(pLSM>gkmHT|28 z10PR9=xKaEn5nOKn)p6gZQx0woY)1af1X+I-DcVAw9!b5Z^}3E;LB#}bqCG5KMc0K zNt(50D1L{?){?Kt-0H8f{#)wAUbxUD6~(kI`Xz8 zMKV_$gZ~Rpd?|$D(~RTZKJk<95x*|>s*|}BGOpFn7UJ&tM$YROd2Gc$l=YT9=)U4y z#vcz-^^||aKU@{ma%{QEt=NJI zp?0!sjmfx6MzN*`EkAOy4>HL?Tiy&7)KE{7gS#|{OS|5cenX!Tp32?TK4?CP{(h2v zb8k028oE?5H|nWJKD+5A0{-Z1luuITRzO?lZ^d;c+YSn_N9Yf$IQe}%w&0buJ@ z-Pc249_||FT|%AAUHYQ$tXU^}{XWvJQBrQS(T?AdZwJrtra2D%OQPQtO1jz37f3%C zT93(_~b4;B$Ro&HD{JPz!)Q%W$b?j zKmH=+7y5G!f!DBe`h8x8A8${^N2I*03(B{S4)#lxQJ0i+i;aO6DJ$=-|E1ILQ5@XA zyg=S%h@G{5;-6dd4#BVZmhaekX+ziD%}366m9c2I{1sU*iY;*Mm%HnbMYplzcE%3j z^AYSjzH&hgHnE2^u?3dV8 zYb>(X5-j>G+9XdXznIT7%Nm_;T%O#;)gpTkCK|HR*TF12YB1}X=*F)|llKz;MYwgG z##k8NbO6~%c`5rg`Z2PX@;1tgEG56+On(O*6`3Dp3`};V)+M{xtEV_WAK8iySa8t= zNt63NC0+1**VG3acPm@>c{jn&ZukNQzMZ|{BP|r)77HKiZWg|6CcYx`zHdM49&+Ee zhY&gFb94E2U1+kNb($M**V|#iLisK82=S?754hXoo89d_?|)2&CnE1Xa<}3u?snHe z?DI?Rb|v8t-1_}4>wfCi?`>QTAARolxrf!&j-qF>KJ|IQ_soDgvDdz-;CrUuC&D);6d&a*d~Th-u(~Vo zddqi=dn~avwT+BJO74a>eG#wei+Ip|-!8@%(tOODzbtex_iZ%S;;nupbDQ1FKYh%V z51rF}GF^AA^pR**- z(?+-Q{3g#opy>rwtSdyrKUpVp%UU=#^&;mqWF@)|Z3M392f^D}dsxeNqHCl0 z4cz}H_pIx?Z6U!TribRkw1U zVlN6fpRmrzM@y`?Otek2wtNvQ{;S~ zWcpz%X+G?%UJrcn37<$?$9sx>?s3u_Fmi>=t8v)kqF)*57H@QCw^ zC>zLR{ffS$*t0=@Z1+!6Et1!x^D3^Xjy#RLbddd@Ilx6O+0s7W z#r}1H3f8MAckLC{mpGHtiR`vxU)J4~(;gt7@4lS&Ef@RMH5B#N_q8SCKT3NIxejgW z53i&j+a0cU*>fiEH+{2m+Uv1P)8LzO%DtrAAa zOOvc^y~h5P#tGbaKzS)UN8)kp6%qYGuEWY*`&T)JU2WvueSka8lXy?RZ@jF3BsRSP z|2Y3gfB*FsdNGrCE1u4F8}DTDpw~IT^+9&As;e%-=U$)Gu@-zbX}`#3EbU_5Mm~@IX=MMT1Q7K(Yr%l z;1?rCjSp~N*FDrJJQG_sqT{uVuM+RLWbE6|P8n496X79y%*3zkV9ovKJj+=`m-V^- zNap^c=fj$wrhWRoS+XC1KG}+ng;Q4wyb3tNCy0&J*ss6A=h)#~RnmFhj4e{ufx?%1 zcvnZ;bl*f^@P5KG50;P{B`u@0O>y7Y2sV_QT9;=m^;gTal^{hc)NzLft_5(yXye^8qx6(ZY+)f_WG;}?by%3^@|Ac2U`EYPwO^K#s%h8+jV}!)9-;3pBFy(URp?fKKhJ} zexCK;pf1`mghD`)#W$`){Q~tmm?zg zj|0!8`@zGr><`PY&uQPlekwUHXhTQtmLmM_C$Kwi6?U@t%IY(o7~iHa-rK2|_4=N% zM)oO+4Aw_*zV&8o2=g7K9G&~e_RCxh+7qE&?)xLTp$sAD*eLopGhRhv|@3xb<&@5xAwC~av zSf8hjiZ+U0b{(7oZyj{^e%of7-fkaz%q~aF-S45VNc&`88T!~>q_j=a4r$XxX!9&7 zX$wssP1^Iwr%Mmxnnr@(Gg{TX2@PLkZb`dNUKHL!a~}LEj#8V}L*q>4xGL+oyXiYl z-Ukcq@h07W0ViwEL$2y`T;Gsa37I1fd5uu=H_H7ktXE!wChRu8mHng#{)I_->iRw9 zos3V4b6b`Gt44RL_~|hAwVfj#4V?q|Me&ny_8qviucpsBK|C6 z-!uH^=hurXXScgcX15o+n6DJf#_Xx~?^B1={~Z1J>rx+OWlSg}UayZK@?IydX|+yg zY}1eQ{0U93kpIiXWq;8JtDox}@7YHo_oYs_GFg4F&%StaN5jutDBhY#TT8}{M5okREtw*5s2(%u7)+5k*1X|xgU-m$&tWT``ra@~m_H8=- z>U{L@P5&gl=$R;daDz_SOYem45_?Qt(K7?ALD=3U

hJG9B%8~@{wq+i7LtjC`fJ@i4Zl#?<~lCK6{)HA<3 z`;yv!WwPsoZgYUnG4rH8W*$SH_<|=3scR$S&0DlwqQ z7pu5U$IzYL@Jf9jtTu4Vo!T~Rh%Jph!O(4IuI8sc@o`&1P(d#!HNA@4{p8!)0FTVV{l2*OI4;a$}IG=+!&W{(C(> zvME9jM>Lh8Hy+kJT-5jcI9K~Ye4KY_v+S4M#~v@~uaYj~?hwkn&04nj8DErgtZgWb zc`$wBC(!Ttj!sP~wE;`8eMCpz#g;4&6uQTFe&?PoeZ)g+P5ii4 zp5HO+`(;RYj5@cOxMj={+5A+eC%)-0X`whz3q9Cc_QAEwcq)0nM=1EzSB-jpLmv4i zIf?mO(9!>oDrVBC4^}HQSY|Iw%1 z7i>EofTwCzQRh6x!JOoX-Lcdu?-|T_ioiNi0@11bfiT@=$ zI|{F5J;6phB+p{-N_sMLhMzP3ZV{cppILFyn%~Da^+&F(uXLN=`{dhp@_FbtqN`7m z=Y;U(+3-4nPldk$<_5y=t<)Pl7M|UTPu9TBTT+&JoNYPy4t@TdHktwZ_sw+tSW8mc#-;^wH*pP>T2JE zy+}shqmgx?ieKuZJ@VWN-vl-b`5&Wfaf7zw2!686Qx$tsRSyL7x}; z+-qzjiuLuu*CJ=44|`$^xyo9h;*M}#M^X$JbL$B*pZgPdbQu)ev%Scsk$p%3#$qot zY!Ml77mG0t$2Pq~9?9RH!u*Cdi_Ln4=XWmk%MQGVUQV;MH?p?c`Yi8js_pCzQJL00 zq)Kqf{?JC&SC)c8Ba8pGV|0Q-&t#qMnXSmybRTaC~lH02ORqC-LI zZ)6Skk5Zm|0p`lW`+MaXS=~cejt*OO{t()%Iu8&Jt@Ed>^;-3MI`G?}El4}2>$qZ@ zvIu4V5jclE{#UR?^wUQ8H{jUN^j6+ai~hd#Med4aeSAH#@G$=8APYCL2=zU_4eiyW zzs0yB`OnZEtDgz{8>DZMb;beA#n2-+_TjM5f&CDBbrJiY#5x82N#FCij{G02c6ILg z?A&9_JRCb&=XVsoBK&hQcNYG&z7uRY2tN4+fw|@*1Np8#kM~rLC{?$J`b1YZM15z6 zv?oQm9#g;_r;}E3uX|lepfJmEJt<4pq{I&Rpf^;X8aaPWaOSM}@);jC@)GlkWWVnz zC-FVXwyBu-CFR%@WWKfsyra`{-^)v#|M>4?^?C0jd4AvUfFq)51N1zxMq7Ake#$1H z!>L}Ir?ho5lF<7-Qg8XlAsXM|+3@+E^(SvCj&fyRI^oP>{buRc{}C)m;k&@_NHzFb ze~OtlCaX||Fa18}yQDbPV2y7CyVAyyrY-&b-$_fO9A&%GjB=bgSCHbO9N)=xr5WW0 zO4@wN@!eckno;hy*GcnGj_>Na(#Gj@a#mA8N+so>rz>qt)@!ukVSJ|)ALYh`rWy5p zgZ%(0wUkQ@O*7lqN?If3CWfY&?PG62N;BosLetFly+)d!a+#rNX8R=VH082F)6Dkq z{x~_H2CErr@VAk}9^}w^LdvP7_x^>w2qWd$ne})4HPMTS+z)w~xEe(Nars_)2|ZM- zS=eO0jy(=A{9q6U#m*d8l&!j9V&bqY3nI&VP(2wmX zI7FUM9hZ0fp<~(K{)k_OpCtawJ*0ie^9TGo_@VO)-XqlCqces|AD8#&Tcr)q=#lpw zA$|N9dHd?)8>I~8e@Q*!Pe}Re^k3cQVN8votnn?k)M0CilKj|2kHU5`pFVh6$|p93 zOC8uoO+s+Udnmyt?*wFyC^#iFXtg!HM>+YvNAgITUN_}$2tLZc2u!g*y99hTd;*~- zSq-hr;`tfIrak;*u3&u^{$-1PU@w|9h>sV?I46F_eR?~2--7)+1YBezKZSlg!CAQ0 z^9QSq?`g!ZdyYC}%_0^YvQPFI<|7_?H;|(6E%dom%Vp?w^*7!R1jyt4d``Qp5%^fY zPG*f?)@ohM>k@c}bg0K9@tQ;Px=DpCWY2KGbgS42^Giq@0I$E;1*Y zLiiu#wdQ2jH>0wqqN$E=J<2~>Xr`}fCyUQA$Zyal$w9{_(v6bk)gEfo5 zH`V@&^fhU3GVh~h+;{<=i@aE8F-q$HFxJ2HE1lO}U*&f~xde$e@{T3b7>lFVqq|STD=SmEz^9R(4&#BjGz7Oy- zzX-gpZfA~w{gZjH`asrKde(p1svlqXNwa<@?-o7JB-HJve$gr6pS+J&jYHub>+ZM8 zyTsq@3p13Jg#lqI#BYFZK#l| z@$`G4F9rJa@n@~;$09QuYg9s~&}{V`KeP*d@=f>)j88&mEB9eZ-;sTMGQY9<&RZ{X zrZMGZ9`)b=`A&TJ)hqN{#+J_S#EoynwX2cnqI@H6hlcm;!%xb+5YJHd!C=mrJka~Ryx-Trxd$2*ttgR>02W{w{dZ~MU*()S@ z^nF6)lYKo>zm@+6^-BG+#%%5F*-gK*>io!lGp8%tgN^mrd7p-T(d%aoJcszpv}NsR zzJVSf{r3fZ4N&-Y6?mWcT)Ejk8Gk~`$oCQ+=2HVr-dJhFH)V~5eQ7uS ze(gWtzl`bD_iImq`+xHLwfm^=f9m_SchQSc(CO$)?|ab5K40cabA-plv%@w^LE&TUWG zuzB%(%PikZpWvIzpV(thHiGYM+9de(y095i$2x3=RYx)P%DNQvP?tmh*0u;5q@KH| z$HzB>vaa_p@HBj0?Jwd?2GLU)TYRRC@D1VY19;|n_|Z18b-q!C?eL9O?d!+UH}r2? zj_bNB?O=>42;dj%@8CE?Vhr`jH-+1ff$&)R2mQ|Yp2qB3P8WAAP;U-$ka@7ACpV5{ z-6gikNBLy>gwn*npx;TFe`MX`z;l3Od%EC(k##k|y}*5Z&W54VQ{v%($wfLT&vm~6KwC-#-dT7z>z_t>*FvNG3D%3Gd=BAJ%6nf>*>Q{~ zkMj*ll6=?9+^h53ZRP^W%$xoLx@0Z8^Xx9x9R&UWaM7t8_-L~=R=Lmv?8*fEp!B2k z6%XIdSZUcIX|1e*DdrdRfQih-W+nTQ>YO|?zi8gWPsRyrez6F7-DnH8l+kzaV<$`? zpXk2-v#RBGXpr*kdu+LQhJ9(rY;|`FT{c-aif^i*tjv+d>tWo4Go(!=&N{k&H&ZKn zfK=R97W4yWS_s^SU*Y5%{dd&GLRy?oxT8zi&aW?>KQJXhnadJ>cehf4-aAH@iKBXT5#smCg4b zZF}stO_{6Mf0eI{Gsjb`Gsk&f@cZEQFVYU-?c2oJcT^{3e+Q1<_!>idGr22H&Sg5A z)AqcNZ@4$O`K}xsqC;`?Vfpq@-brPHPvp6R{$AiR@@hG%;3RovF6^Zl|$u)|cUr*)u3OFTch8ZM@4AeBYC{ zo4OMKpU^GiqtKm4_}!2?_VCS9V6E$r*ply~@9#`w?-M-t-{;&EU=Bh5YJVU8UE-ap z;C>tlAiSPWyH>5od+Je9OQn8=)e{k%Aui|@p*#9N_G~dD29)*rfhdPvX zPVK(~Us7zI$j!-l8^SNe9yED3_6qhSnZEw-8UE#wgN1u8qY5KHf%*15aohhx06UNns7!mB?~)~ti}$-We7F;o36;lQ%HB*K`$+#d zdE|12+{fAM7r+xLkDv0~n>?l@8uIXTp5@N|-jl4wAqUa9jUn=o{??m3o&_G-#-$(A z#)?nS#%Bk9d>g;kqm5tcqm3`e7;OyDulAT{c7KaDK4-S^{*X3~>7$Jg0~fja^f0k$ zx*o<&xJ;e1iCZ?l@m1!jAvPw}q^UPw> zI|*7MP5VOMTc`6OzG*&us5bd9FoX{m!O@$nQ%ydMlk`6NK<{U{$2SeTNg0oRmU~yf z*>3jFD9WtwqaOAsbnD~t?qAO4QTmu1Q}+RFGoPE4ORJkp``%-m`7hw3!JEv_$uEiD zD1Nu_lRl#1dq}AFW6JakQ>(-QOCEeX>_W_8l<}uO?qTwzbu);|t`s#^V~&E}8Hj z5H^`{*`NDeej?v*6Uv_JP~3Y=+$EHM4%~7UnfL?pJ(BRK2!6@D$6S|hPFBv&Z%Kcb$ryWm_U)mzS!ZD7Qn;E}i7J0KP z@xh!ba8TxZ*YTsA9fcbQtC#`l9fLOhFc_R7a5+On+HIY)vdCLjURvU;sc=5BqI5;6 zv#OM^x<+-ut82VfHO^x1veGKA3W0lzA6ZdWRoaxATU}OMSY1<9wtVsQ>4oY~t;r-vFH5FBQ3n(O63d@#PmsZu7_!risXBRH4EL`SYT3T4W1iDKKYrKmU z@btoaSJafQDuflKbLZWcU0Aqy`HI5gRjbl73g=Z6FD;-zj7kVXFs%{Qe-zPT&!o`2uM!f6W(+2!*G9T}5_zG6_; zKwD)^6%D8?_ZFAV{diny-Hmo_k@S!FKgv2%@PA%N8&9me1|U?ew&gvTD?9 zIXd$Z%=!5%=NA;-yKrjZtb(+{g&BqU`JXFa0Gl!k=ap606qeP{uTZtQBEs}g(dtdl z&u10>CVzYfp#MG0A#d^*^BFyG>HjO=Or`whPvT0=>g?|om8Hv_YP!?N+0`F(c*!zv z;gV8sWoUo5`Uz>b>1k5(_L9<-w_CYyFE3lZV%5arW!@g}s#3bn%2GOgS3N~#%S)W4 zi_4|o(p}7s)suw@ON@Ldq3aEUUz3nF-EE%W9T5ORK8rtkRUO^3bx>Sy@%F zxXQb%XD+1{m*>x(H+PwLacP0KYH?{z0Tf^(GV<=vUnuQ@uw0!0Jw-NDK(7LL}&HVvdT(qtU*<1yUUhUR$#Cfl{h60&gxmpD;_PaDp&$xOZ4Xz zm6hF|%a*UixXoEns;4R?Pg1n-UT>vt$)->Diiki^QNBVfG3JEl8bl!`Q^LZoMEIKr zt&8u45%4${3tEIl>*8Yy6;z8oPftthp91qsm+OzS=M^G>LfBGRCekUCq$+xybGkk@ zG2-;EtST)o({t0RO6Q{T3UAFFJ%DA)YwlR-t$GX=IkDv#PFho3QBhTL$BN};iz=#? zIjg zscLc29g=%-dEu-o@8VoDKZP?>^}>^i7FSJlrj5VjOR8J@y)}%NMGP7SsRr-+Aip>I zthPa1+N3GY3C>glh4WTt`Xs6|XqsP9U1koUI!Q(z=$Vu@(a85D)t#>YEppL$9ipzC z0@D*h^tLmhsG_3W*{Q&t;JySbvP4uFOR85Q7Q7Qfyp_7FI{}%_Ij~b_l+K{r;H2|* z=VW14Mpsn8!eGhhtf0iQvQ=;&iB}@+iOxBb9({cLL<3Ldq{T%7S@jr@>YCC@$urRj zczh>{notxKWPMaJRCS?1fhs0F_V_9b1$m4dfAG*YTc(dp$nCsMsd)s%W1?UBNuk(i0Qy^<%g0my{Q{GU zXT3KCIu6uJZH!Uq43X1g1MHMw}5$B!G#k%>$ zW_g$AKeEDGo(i6c&Je|bFcXb5%_v?|QE3*(ELHa?8=^aq98$Jyku$YZf6Oj#G9)?G zq=;sY8;75)Dwokjf*t=|**D|&r!1)sIxw zqzWpL@Xf{uq%zT|6D1`Lsq~ObkFl=L0kFqVmyu_Ta5o(m(X$M!LC7fI+mLAV;$_}d zh1C^>i@Y){(vfMInNYU8D*+=T35=a+UX8O%^4>u(!#b&oBZHp)u#x_-k^XRJ zx-Pm5ysAajI9a-B&Pdg(OD)6t7_o=Pi=paHzOdUOta!yuMsSRRfqnd>M|B}NaRfqI z$U|xuV4@RbhA_z&+F-G|U4W2$UlME3t9uZNHngZd^zfgh2HnT!|8IKGi*|@J*N5L> z<<|A1hqw1Xpdq(0B%mS;QGMx%Q$P>}B3!OsW|DlrraW*5tFMWcu_HSypkD%QUgd zS%W)bScS63OH;@9vfib;EgywfmFkNxdL{hFx=8nRGBdrK)Eh{ZMJuN*wJtKW`dS?2R^r`97(zDXDGtwBvGBPG-WM)js zn3^#yBP%0&a@yqd$r+O;PtKe?W%AU?(IPHnvy*=ZEE_|jH#2SW=@?lb?Ve}lpIAuDmAD{xbd%&ggcuAC*H^pKS|S^1f8-@=-yHO$++B`hp1 zWD&HKiE(B5Tvm&+3g<3gS+SJmtc5jGYF422bMNk1{Si8qXCgvoo^NC7hNqg)pyk zB~4a~to5a;vfGQjRVAbw>rLh}AI*MlxwnYLAl9$VE<4+OFH0#a%ZiPajIMN9nvvBO z*6Qeqj|p=A<}PPW%zE_W$W~I#WeEr`nKZVfe+YhkT@0I1xumSPn&lOvytx=8EoM!u zL}ndEg8Ba#XpAJz_d0qw+6>2J&REO8VK!#9fY!?Cve*c#~qaprDW;4V^lDB zBSNVeNx|S@5U(LzGf=6+gsFp-ddL|JHpVNplW<9bQWpsK5{^s`1~-CZ9^p>H&4kT_ z7YNT1UL!mOA@fEDgB!xYI|lrOF&wmVo$vtRNH(}`9v=+OC)`O`LYOuIyoBY12ME^? z?i2d>sNkB^M<@+^h>-UtYBOOf;ZDLCga-)c6P_Y0A-q7iitrlYX2K4_M#A!`&_TF{ zP=lU{(}F=4;ZDK=!fS+np(_ji5FVaR`-P4f&<&rO?+gYj2~QE$6FziTFgT_k`CP$Z zIib@HKL~dco+q4_3tv&)>x4H3fPZ!{_&}6Wjq}Jy*ijJ-ros1#d;oV@N!c&AAYs1$G6A5SR4F^yFeHqyiRz7a3TlD zCJupq!ij`y2EIOXU4 z2|bnY@3dR`$rbdDkf!N>w#V7ZxoVVcL{yRvO9Z<47HBlnCErAT`+&_bVNOC9zq7#R z5UQML=hNCQhkJ|tzQ6wE4AS9EBEJ%e(4SH3&OgDohToj@U=X#^{{&XcFAtcNS73Yj zxqzh-%Addv@_VR9zEi*+=m84=D*z_#kv}PWgP#XjXuXjbA;A|48wpJCSum+T4Vd7o zByP1gZ;So2{q+Xt49GJZ?j-pk@+QKY2PE%325;v4^)J!NZN!BZA9-p*>c|3C53CZH zwA-o!p4Qv$ms-&JoB^{sWBHviy=|u{dzrE&QkFld<1#Q;2K_;YK$98T9-lu?mwLpG z-)7m=2$6jzX-NQ;71y;dZJn_xjt*qx=>`ppOfDh z@-&hsi?~)vp4rhcPuq9d^36Pgdj{=17=k+u*nD7PdXwEfo$a=yn2UK-mHcX@F3Kbd zzazn%6FvXw{=53Qw?x)Qw?giMxHeC)JmRGJ&)_@$XyX4Na>93E#Z1Q z<}p66N-*tXmo1zd+797;4f$MO$7a$V+N3vcFuV+p=U4RLLgjzb>~1aW9)~+@o;~bdTLCCU=fdZO-y42+ z_&wos!slAHuQ#}ozIvK^GB+{i8G5bjM{cKn=$$F|N&8c_QjmwL;zY_OB9{};xR<#0 zB7?sv8{}IbmbX>=ybxp>JQsOp;CD4_HuSNxO*`y6ZEk5;Zf7UTl|EHN;U3yA_SgrG zv)^FMH*}!~Uj)UhryNgei~IknyAIp$*gy@ykjq|qKKi@yZq72Z-ckz8MQ{E*y@hVm`)E0Hwar z4jzau{zlK=)ds_a=zP%4$`1Qd;X)|iJ>aMn9O$9gByEe1qtW(s+^*Q%Eko)DcMTXh z+XiionYBH-^yOF1S@E^R^91hR9$iEHZZlqJ!E?4p7f^@z%A4=t17P%3+oso1YkPXg zuEFjtG4+G;wnlFo=-nQ*_}r}RQKjc*Z;z@v$4G6mD!SGtnIzBlC@FKVWTWp$`{DPM znfQh&;C)`l+iZV&+^(_iEo16a+*?O)OLlK}HYDXeIqIofa(9f}Il^(JH$#{Pt_E_Y$H!O zew=izzV~z|>6b}&lAcE# zeb((0bk*A!Hl;fYjz|Us7kR`!t9+x5*&$ksq zF=3Kc0<0d`Ljp7XqTDT7Uf5h)*c|)3@VVi0+@UqZ|%QVt?#koP)yuhY)W#I?gc?8;m-FK*0M``rF7%LGQBVvw0X;oTUxIRAJT?*x_w zY#y*s8!!*p1Hg0{nDSBckiqPeU3S*KQ21?5ZgeqN6CG(oCM;CgF-w;O zHV2rjX^1Y$pVYI2dc@x8^QbTC^#p8BkK8rFy*;5J-o0gb{jmJ4iQ9%g8D}q|zE`_E zRKs5G1m~P%ADLT=Lk44*Yf{H4>Nxu>YZi^`0<&etD3pPP|}_j}dykA3Hu? zBU{OjkTq*v+P`2HzH*rR>G`|vcW=3`{@%G;=WV;^$vIEW&f9)>!`vOScIG>>dmSG| z#uJ$eNB+EPY|0c~04srSGS>&U?#sKy-^$%?Z?NTx)1@;pRJQZUx&hgq`Wb6lqJuxv z=`!YgGK10QG9K7qsi1h%Ry;@Mf{SEQH(<`W^ZFC`Jp9gsGxadOm)@iH@h#hC3t#^Degnvdm+Q>igChZVAGm`bR zjo?fZg3Uka-*2agK;l+B|x#H$OonA&(2H(WOcsb+`f zi&YmK+QxXM_4{ls@oHaK=H__i3*RUYJ0mo1hdUdg`Qp{)$V`Fs(;``#X6LHF~$D8Ag#>UJ$OBe9lwF`E2-fpl*8XEbK zwo26qyH#+`lhMtno0MwX3{ z8u87Mg1|3p095>cg||3591JB9n{6j@)%8fNEk|warx8b4_T{L<{ZfhF=%?MtR}KBO zK)yQF-{S{9K--(6&JNIsABghQ=Bu3pH9sFX57daC9q2ijuZ~A+EpBxoS|ffVI&-HR z9ZDs&J|>k?S7J8XcIK!JL$r+)9-@hvYNztlfjEu$sW{JO zDvsASy4BfujrfK5RNyTMsl=}&q=KPksOJQD61B~4bvRKYej(B0gXm$}=6rQ|m`1#9 zSSs+A;S=#VN90||QyWKmd^xIZq;?}u)!w2JZ@49ujF)fmoTrVWvIM(Tk(Gl^fjGgUC(rJ)l$@5+RRz+F=Bjk}~4-%M%6hMA%twKJt%J7-EO z8fOZfduNKg_wheUI#V>Pd8X)1%S@dcGo=-$W{L`*o+)BHt7Et@GZPs#x&+Swmnd(u zOEjs)C7e0v5=A)dlCmdUQcH&`k2#uK+n1-VxV6SSb;GTl&Q-^APau}YS=!-Q>fkIf zXu%!BY=g5-+cw&5^>(cRt0q>*uwL}V9T5$-7M7xpM`)*Ks)LdHh#!pJY->Yp25B2$ z#h^6e2Vz86Ct|e2s6mXjmxd44Hs`6pU{Bjjb$W=lcb2*`L?gZ-*5h-j8?jpLEVVgK zBfc-rvvHPch}RCf6o#1i!T40*n-ezM4xo`kb=eQqh@Tjm3X1wf>FgVZX{X@qFyYkR zVW||mHq3JnjU2AEAc^5Kh#wx2N-4V1b(eG{_(fMD-h7Ma#7xyVN;Ko(D2@2}QJ%~B z>O_*ZZ5F-XdQW~VS+}yaY8ECu1)Y@5a@M2@ZT!Nq2tz6ur*IirEJGU&o#`#ZQ2dD+Av8Y zzIjqAW&M*<$+`J<&*og!al5uLSJkI!#2eF)^{F(^&Y9|Px^`uzI-9N$zmP6PH)Keb z;~5@0OUq>KJl$uqbe!}2KU3Y9EIBV{N;f$>Mca_e+hge_o2Pm%yH&?j%||8EG~zp_ z3H)!A6HAPFE$q?@o!g+$qBJ-zl}9x>E#o8aOoTkbvH` zuiYs$wA~p)?Hlis8aLl1G}qoG0->A3!iKwq**otN71(=MDm0uTl}>t>Xzba$G}P_< zU80N^?h+NlARv~@cZqUcxl1(v8s=iAx=x;%s)P6}F%IB4%(3xmCq39Dy_sI?(yqDG zwH)nQuG-+%F6XLRw^pC40&YA5wKHF9LGfm3^|NHGj4aS9Rk`6)B&-ro1W)dU9VagC zyj`8O8~#O<6TB0(`S^YM2;1{{wCKS@H*6h))G1ATsmq#noXdJ6HirYkvC>Nol=bxj zZ4K{;EHt3c(`wZG8CViMkI*zx_8L5(?bTF+P4j8$giYetZCazId=BlrgOep9fpmz^ z6x>l}E1bBO;r_ZqI~Z--5H_(sTAhf{u0&&Q$Z!D2dM)>Hg2M2&7`h>w=Hb3X=nSXop$Y7lsatJE=So;I5bwL zt~j)_18g+^LX)qUz7VfiY9fPIn1B2COkPlXS!!(@#+VFX}s2d|RUdA^>i0kT)Sap{FBejh~RNElQ z-!M3m{EdUfncX*7a<+-5+Zd}Ij#UR^1sSYQXtY06>kux(5Qj!|pU&iu;=b5K>S&JLXFEPjU5V4K0E*X$Z^T<0hX0mI zrt9&kKn^5~gw7KQLi4EvDSSFXa-K~P+~Z1E)EbAW z8{+Dp#|34gXecfoQ z=c`88XodkZbZ#`@elt{GGoD>$c-;)u=Zy8qL^CvU@sfjmXY%J7Zlo8OVP%r>Y~_pD zY2>Rl)AyQT3>%L>{rf+U12K!b%f-{<*`oMh54csTHr>c!J@4%C{KFp4zv=OOrpNQe z9?x&~c#h2IUf<9j&tuJJwgc#Yx0}zrEz|!3=7&yG}HXof7> z>3>&t8}u0ev(KG((()(ot>rJm2-HwBREvy=1&{oq@odrAW>(BL3H{Hi@57)$|CN6; z;6d}5^%nh)J81OwJ@^IVnREX2=gxY~eE(fRs%c05yYPLA=M!?^aWmhip}~kx`S2+p zgae=I!KZrgsUG}q?+1702qDgCyo z!Z ztxA@BlyMF9o~W+$ zu*1KEfi~>31-I5YI!yR=Grv{4!Dlw6^uS}l2dVkxR!&1Qvh3NLUA5%Z+=EW5A2sf^ zBx{77aC05kN*w@x>0gZ|+}I_il!1S+I?-$YVyjRO`mOd_aH|yto{x^36UksxU2s0_ z(Eltx_$n<727E4$z45_nSMB>I0yD7S{_k{$8~9_?8eez(27I7O>#<&K!A}==&u`%m ze9#+yRt4oF`H(*=e{+wK*}|XLNB%ThcRW`9tUmIecJ!YAfxhxU6LAHc&P6pvTD12DBb}=mEctRZI(Rx!^{ARw=*R z-5=Yn=kJ1B>zfH=lYSj(=C|OROn6KW_`4=Nu?O7C0<7S1_JIGvgs1j^XJbGle_9Xt zCKI031O8_d?&<*_9cJK}(*wTPgwO8*|Dg$gpa=YI6Yl8&xBB}M6K+Z0;PasWySeKD zlB6o{4Iu_4$l*aeK@1|wsj#;_`(FibZ@2euxxKsPX750x()7;s&i38R^w85YyNedN zq^L-gq>#cYL#cp4f*Q(Gi-cIQij+v8f`3X$MJReee7CUQb&)ZV*IIa2fgPqpjchP1*8}ss_9NvMjFYpK0CVXK^Wi z$UsN-tytWwY4nHWQ1Cl)a`=rxIoxEmc)UW#2OXL(!9`A5jIVO}uV(0W@!oA1@B9^6I>LwR4fr7gF8gsZt~KV5;1U;n&49ld8wJEq+0PqiLN_xm`*=d< zUkvy-7)W$vzfb7g&iGTj54e@-%XlBojZ66UP>yfI*svh_vfoJ0!P2G6Z?K;D<6?ep zczYJVo#|Z2`;qiqCSB5>`CR!|V}6yq4d{aOd?{VijLW{J$dAxDv^CqV;Jy7&u3aka{SSJ*l68f=tpg|9xlY;f9Ce}9zlOj!GqI+@8*7TS_Kf(w_V|4--o`KY45(GpzzjaOnrkNgnXmxd)!SID^R zLklkSH{|?k`aJ=nBlu>fb0J&-!pFJ1;F``^){!;oxvp>v${$S+TwlwU7kN0mEsJaV z8?2k(m&K*L?AvoUtu?eu@+o*;ex5eS&xN@>%!kx?&$I-;lpFXIT>GbEj-k{3&L9gEh5%d#r$=G?lV-?KOx z-wx&SZ_>|aa&%1cEaf-n=;S}U!^Ek~;QGb4c@|M+~*F6)zQ9%BDJ}-J6;}S;; zpGSeKb;RQm|9_9d3-Xo<@6U6-Q_+9+`Fvits&G6olZ!iA3QzQd%+C9mPCgH;!-#r+!LY{0QUs80deN={)m(-3ZL6y1ry6|KChs@}(^$`qoD1SDXM&q?O?}~6tUGHUF{Bs%C1Hg;;{Er6wETl+^%8w}=?S4|X zcbMC)8OpB!FB;cfz^VTdzi;OGdN&MoQM>Om;2$&KpEKZ381N^7zZU+Iu;zMg0GvDv!A7 zFLk^0n|5?PXDELWeuKA&58Dm+3UHcV$+sWk`8^v4t_YWW(GlIObrtX;`o9OfsQHIa*mwglA&s*@Ji2ilJsXr3$sNcr{tq&Q>KWf1L-GKkhfNy+NaerQC zz(*90yu>A%k@TBJbhQlS4*{ofNjwhmR@YsI@{byD>pbcw=4(Q?OTXDe*QEbp!qf2K*rd{#^t9Q-#AW+^RdHe)AU}-;4v2G_Hrw(&IXf4Y>!L z_?FkJFS)#UzP_dCqz1|#PkVK7`3r#G1HMUK@o_G{&rp8JfUg24Js|rdFi+~b(@_2s z2K<`_{71lx^w^mf=yqj)2jZllJ^t8?xT!vc)zCql)hPy0w?}UUSc!j|7xKBzrc(1*k!+4+|Nmcqd(u! zgz0xP>AJyC{^JJxYXtxV@G#%2Gy%D9JlQ2e=D15D1k4|q|#4;t`q8t@-5ec4YJ`j1>( zO#eBBgP-r!{kim1eLwg0n$J&h9(!8D)||rmkJN1yIE`!YBN~)>e}L(1y+AWe=>NTe z&Jo~6a(=-ZG<`WoA@s+A7xC>j1O91+BTviY61)Fzj2}9K`^jT_%_Tg)ynjT$|4Ubc zamkm8|G9HB^X+zBj(#_suJg#GTWn87Km0`D z=@IGAm%h1}KW{VOyAAkt3Wt5q&DRGFBJ)47AYeD0;i{d~Ov9|lf*gOOL) zCYHCGfs?-^=R-tK-ff`s8C8CxwS)7?QvT3Yd!OrP^kQvM>~MRGU@ zT z81SDO@TD!qeE1{aMeFE(L;24c@Gk==`zYsm#2-6lkooZ2S}zHIu3$W`xA!SL#Tfn= z0;l=fn$yn@8p{6@)4zk~Mb_j07|Q>aUCf_z4EQAmd`97rf0mPF?*AVe%HIe4?Ec~6 zH>ZmG^A+HrF$N zzMK!)!FpgC_$#d!d}hd;n_3pYbuI}PREDdq3e zkMmi_TTy$r0sG0^!U(~&&$V@&7Fk>Y-y4_wXT^SYq;b&INef1YsFK<8ry z{Obn%hX(wY3O~a-hxs6Sc*Cfc6FIkrWvH%c;AA&9uzw}`;ef)qQ0jJv(BX4^Lgz6< z`EMEUpBV7x6%KpK^L{_i*XUR={~d*69q~TJt=!jZfz!O?^ABqVIv?ipavnqM(F4GX z^uyPI)4G#$dN*^s?}VZ&lII(N7t#5sDv$p2crRr--(g(N!Cu4o`4f6vUp-ATW-IgO z65vJcwz#~U2bOVt-cbI$w-nPEQTQ3wlf2(_3-{*$Srm34X#@O!`?Ie)l;%Rd2} z?9>MKD+K?sqQiw!w^zJXmzVROV2iqL0j~VLoFD#q#t(l|m%EqCf0uFDFFS|vbKh1x zUfY0A8SwqUN#5k#nmm4auc7>B4fvN8eui~1^Amrn>o+ei?&sMGho0f}`)V#fYAAn` z0sm72{zc$L`t#H)iu?0=1O7Gxz884Wy676p-)X=PE4*LteGxdVQ#pqmF@N6rb}d(O z4tW#fp9X#*e@@@N1f1k8AHRHG;pvk4^K%CLbz6)1HV9ntna}fxobNG|cMbSW2KJkz*ID{HVkm#^wqpKY47{k_K?8n;fzCCC z@=FH1qj2P-4(oo?dvWNx6?l={ew54K_VQCyxn=dQWqphB_%;oEknxREET6oO0Jf;> z8sH>v*E8QPWc<5^_~K7czNkN+Qgpa->h`#y{4WjV&zmmh|LYWveH^x5bKJ&thVo4V zemm32?=M(eI_+pnJy_gQt5mjlUQ}5g9lop{G&`%8)ta3x_TZL*0sgQ5+e#D%1EF>C zD&FHn6)M6+tS+voOdo1Amqc4yI@bt_)Ok31Kzgk4D9sQ<*;5&_i%K3eMh^ykbK2&3EsOCFB`^d z#N#lU4a(kZfR_c^_6;4p=eX-dcwIKSxP3o{*hgR@#t3I3bi^SdBdRpLqu3sqZg|@| zOY?QF=}&vH=gc*R9J~_Qw&$aeUdOz!*7BXwc&(1t@6I;7n!iAA+Kw0e)wmP+rRhCR zS@ZSeH~Qj?)gJR}^(pn5a5dhYJNCXv11xUoMHmBrI_o-+L>Z1$K0FJ2ua&wr?v|!1WIEHYH`u498`-btEYR) z);-V+L~)Kr>h0`Ucyq%oFNpBr#J_2My5w|U9K!aCMR@Rp6Xuu0zX-e#$|s%~Lb=Bc zd(55bG%IlsHr-{fiTAumvoqadOO6#$(k{SWC1X>=Fn2*Ywg=nGUgTHZRvf`J4!Wbd z6pZY?db#8}u450nyWED?gg{5m-f}$QPBz!vD$FLV>ZA)A+PMUk*k zbOcL8q~Roue*&!r&2D&5yAjFo_kcebXP&jJ^}5dPo%`xtXV9(GrN^V>`FK^^2G_jU zcY{W&P7cYqJF6OqX5ps9omSnSz0ycl6U78MPKqH}^`ad)Vpg-~V=a{PB#VV0aRk${ zFu%KOyNPE=179egchhae8MKxRdcF4dLrqjIk5jk5>9pagwjnq zoRwzBl0nDPMH44M57_O*K|P4q)WCU( zvtnjmTx*YP_v6WWU2E~#>2}uvFLY4IMG=Oo7_kvnea*vq)vH$BVRsnZaow4{le?hy zcTc-mzT}6M` z^(r^GkzcnIPb@WD%bkA5?#W%VQz*T#YpU0()a;uk33vC*%#@u4cVTkdoI|>(={2?@ zRNFRn%{A`Oz%UR9x@~uw0peU2!RbL#t&I+3!Wr!}31Foh4z)V5Q_0kZ8y9&ilN4Q& zIHh7^R*4Wf6)Q=k+@MmWN_S|N7f;z_TC>&0NgSiF-kvDK+_oT4ZCd9!qdeVn8b+!V zf=j$>lb&yN+RH9^lO%YvSMJ?OfpB-awP(S#8h)eFTGK;t@oP9^igq^UA8yBCOOJVH zqT+3PO80CI0^gJ1Cm<`$j$2t>wM*_CronB6^`Nrmln~YrW1I-HT?nR+ z<)^~-i5Rgs+Fc5*T76s4tRiq<@|ADgAM%euzI?Ck>v1N-~4@$#ANj!B#}xWgPhJkzJ&^wvCVw*{VO}$htec_Hyhk!g+#Ys{*LmoxuSm zdT?YR&PZcb{n!iYC|ri1RARdwJHWBnz{fa5atSq;K?k39Ltx3Z4XbYCHETX}UVAxc z*3=iJL3i3;@;dcce_2)E%2)GI039FsR72!jksC`o>Bf;4#O>L+#X(2^Z$&T0W5f6noQ) zcrvQB^&-x!Vbt9p_$#e2LLLxlLFCt>M$m*K+fA<H_q7;d(%CVG5ycVa{ivJ?6q1t=nYCJ)JzRRGXRg#t(gkdl5zB$augY^vQTObI!h6pS^y)sqk|+{Xez8gp|&AHvsaes8>gGr z%NR#9j2c)G0cMyK#_T+bmB&z0+Z$yZP)sdAyR_)FgNloZ#p;-?pc{4tR!#)GLLI0e zSV7V^xY2hS6-*6usY=L|rVacZpY*k)6LS~JAPOCw*djFP&mP^H5aE+=!YEj-2JKeZ zZ-g?ob{LLfRqQOA`@+zjEGNxkdiE%GYG(5Zv^d94OgY zKFfvx2ksKHTF94@jh&pI#oDW^BD)V)xQT6rxU#$z&ei0$S=SyIvdAG#FT~m+JZ0q) zLB)21icihuQVyk}ltUuNy=W8Sp;Z}@@z}^vIuP?;Wc0+6^`bB~+5N4u~b^X6+g5tG3zmq(=w7c(UVdGUMHc||(w%$5a%6IBGwQ))q?FqfOGOlHTTxul*U5T*r zMnByTW!|~(fy!v7$+P6LdK=RrZ=2j>rPXR3FM^F;ge#L?i5d1~R&x^9q+KE{Ln(?J zeq?E;MXbGsyh1~ZSdh_BSg-3|JV6_4De|JVtHbCZ)^X8d9css36i+s*S9Sajlmp5v z>^G=Us$ULAmgG8r1P(~;{S0LZ-;hA@b zs5^-m!;0t-b-!2d_(NDDaI+IhR$H};^EqNJkqpqpRK&N}Tgi#WU^%EkHIOp22jO(nX5nB70Ep4iJ|(Y)(x8p;}i5VI{8T zSB0%lB21D`4!4bW=1L`Zk3{z^Z>=68pjaf2cMSQZdF%|rj*u%)Yk{j^S@v%R8AhH= zS`i1J3T$^&Gj^6TIqAGVc7qZ&_lXsmxdnGudD@*>K!`m7w-vich%j6g*B0)g;A>*} zahMcnC1Qdkd|*&_A#|JSL=iHrL^EX&*cRHUECM(O6O06IQ1^A1$o=>==cF1o=W_e@ z<8~fpKQ6_NV)u7U=efwYD?^rlcXfRD7JN zd$psj#A1y!&0C|{xT6=_WUPt^LS*M6ek;6v5JPPAQRN|l@;wOk=< zh%k2?+XO2?)o(hv%t7B$vr8WNZiqIN=D-5T?!_YgR-{K974s!L6xGhIj#47)o*T*u z^Te#b4mKD%ap~s$xce1P z-O-Se@fYhU$atP*7@C%27;xGRS&niYO=u*M66r~LeLOQbF4n;*54oiCRT6Z9 zlAw~IrgJ;7SF;+OW*^tH-u!V$kb^C8AI7QYv`Y^P_MV6tv)H{3RFqCrAdYHs!s=x2 zC8|WMjyvG#t=qam&Gj#ZoUGUr6y$mhJ@c{&pd4{K|A+!NlwG(fJuE)a1P%)5OeIWq%1Knpz*hQ?za|BpwLK#WUAUTvfW*D8bHTYFR+tvEYhQxFy*!A zpg7qT8dpw!)S{3)n_gu`&L5BJ5I;CkK#e-(OePkvk=drqvO`;e{T;Jy6;rYvl&r8M z7m*`Y`{1M`$;dXsZr&Y8S{#QSgnpWthB}91hvwGJ#28T=+aeI4<1*-~UM$J}S_S)c z897#EaO|hUtE{K#tKNLRU^Z)C=w^c)vMTAs7v+iD!BKNx8Q+CXRmraTID`iUkX0A- zNP=wcVQye!l}_0k*0Dx-&xfWcVd-&+f>uFDf;B_hidFjwIbrMfa^RDy6D-Q)9LqvM ze-m$i0(o#KH`+1}U>^6iX;x)J2cz%h%)!|L7h9bMY5K5nvLD{aI1&T)c*Z4GyWQX^ ze7~?64!QeFb_vN=uZoRh@?eLW;YwchP4vt*3%Sb6lb5Zt2$(YHh?v^p#|Q*jw=~1A zm_&*ytWms(=Frf*M?#IgRdq@zV=@pFs_j`s;_gz_;k_@B6H=;ewXXDe-9$Eeei4Zd z!XroN7%*M$Bn>S=lx(DgX*L!@olS!RH$`RzR!DE+>OF&Ik6W1uU++#ZopHeS0+xi+ zXdpGKMwt!T6ThKo+lzwSybaSS-9$m?gLF-Q#nsz7X)kdc+W;{1I7rp?GATI-N;|L9 zGV{ZhD62ryUT|@aP+7O^2yN_#BlpmjBMQ}3tP*uZptm0dUFL>M`hZDa2AhuGCiB0J zz{0UG{gp=6J6Fz0gri$Hw~*oxEmti$cm!xIs{bv(Nzd@!8 zcXoS^DU1hUTUqI0axwE$Pb7NIW?$%(iuLp&?D(_{X*%dQbi%)MzB9=HVb^^<>CRD| z?xbD%ef48WHY*#PbYdJlhe*s!BOgYoUDF{#dl-i!IQ>FP*;)S-LF%z}q_@L*33}pT z&P7@06N0EYh7Dypbf7wm$t0HNcBzL+E|eErd?2%LDW_-Vc&y$iXPTi2X>90K-vNoe z$EE!;J*6`hYW?`lYX1od_u5hk4sTe6#+`{m1PgVX8gAk6B$`g<+#Xb4l44~O*F>Iur5 z?xD0PP6EWSS6MDfKlFU@W6laK$m6);7df=lX-(yf*)RlhDr~LkZL7Ak$S0Ga+9_;> z3NK0!J0lf3j7TwI$(@Co$N%IOq?Z{+rqgmM=doDL^bW(og(~n5Xo(z;BgICgcf@G; z03L-dps!RxpCKjnL&s$@oBhPVM0gS-HJGev>;g{V^&aEElLhn;#{!+0Qq1W~T5AsNYp&oBl)Kk& zcPP<4HHAkB@Ek*CBhgN0IYyDfgaXDyAV64<)38(n5?bih&<>Sk3UxFM?X4t-kEG}W z>RDY&)C$aMKC4NY9M$wh?@R-YE3=qrKGL%H>*4pnWl&E?kYj`A2oM-GYud5NGG9XK zpqiXqLy4lLG$am^IyG`^mK7-_6|8CDO}Lrmq+4s?Xq(<}A^pn^b7={m5kYE2Oed2_ z80Cqgj40OXb3yZ<=(Sp1S1Ds}QJtT(ODfUZ(m^u<0G+hK3H1s*u1sgv?V?j|ML8Tj zA3g8*4Xdyuy(OBkSJHsme@^lJc$~Cjn-iH%NVrPhWgWTv`b6C%61@4{8y3IRLne4W1R2%#@-et3zWzyy_CiSZQprkFO$I`KJY>RIjBL=8 zU+J{Wvj!Mp5q3nNCtfH&U|9q0wFVxOz&(!ieOW%?FsVO)$8!c2J3+mASx~jqU-TG* zHBen^qNcvbk^ZKO4%5@Vsu=&_;yawm@TdZRYSm+FfKt!afJ&zf&{J{vE+jK%4fxCa z9Ncmhb>%M*t>E~UI-UjBm2|hFp&ya66b<=Ibf{5~R2}s2OdslpXb}GlsP=VRi*T0* z@Yr61&WN0#>wM6mSDBs4^d8ecyVHBW_{F()PRsp`pVP5^_Wbjq)PIKS%Y749_zkXi zdageGP7{7@ve&-6r(EvWzeZOeGDJh_%kNEXWn9{q_nFK6*%At*F793r*?~{br}{7N zJ(v3}Oj!Ca?Z|x}>OYsNFYiZ}`-R*f^`HKi{^O&%s`!_1p(pQAm-~^I>2lJ()R*x$ zx&Ag?EP3Dhk_MjInAHCre9YHh1x8(bi7wWAFT1>-U4G|{zgB&f&vb9&|8)J{dueXe zrLI3y-{oKVy*l~(CVWWOzy3Y?8@bOvE+zFnU;pM@eR&_e-1Fs$*XirM_=DOP{>yvg z<$mug)1@sdPw)0zeR;pU++&$ICX;Xf?p%F&553$Mc>cJ0Z~o-(Pvq*$`|9O>bB_P{ z_Wu_3UylE!oAMs6hyIMXVp&_&zsWx$KXQKzU!8^jrT!6q|Jf0)FXe=S{4Mt<@ddRc z^(}cn-krMr%`!1eAkY8r04Ld%`tshT%^%YBujl$QZfRHO{1A21?aTX?Zutn;*EeoG zSwBMOzjF1TzDqaw^j*5*L$a`#g4C1ykz9RwU)A0B>H1r_p4_D0^7nK2K(u81@_wnO zxc(tS|D`^?_Lqtb3cz=%kDpo3TtY5=&rOjkfBIkO5 photonvision.service" + popd sudo umount ${TMP} sudo rmdir ${TMP} diff --git a/scripts/install.sh b/scripts/install.sh index d386b4e1a..e988eaead 100755 --- a/scripts/install.sh +++ b/scripts/install.sh @@ -68,7 +68,7 @@ Nice=-10 # look up the right values for your CPU # AllowCPUs=4-7 -ExecStart=/usr/bin/java -jar /opt/photonvision/photonvision.jar -Xmx512m +ExecStart=/usr/bin/java -Xmx512m -jar /opt/photonvision/photonvision.jar ExecStop=/bin/systemctl kill photonvision Type=simple Restart=on-failure