From e1d5609d3dc0cd9b34d5ff0e88fc7446ffe27dc7 Mon Sep 17 00:00:00 2001 From: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com> Date: Mon, 9 Oct 2023 18:38:03 -0400 Subject: [PATCH] Refactor FileSaveFrameConsumer to be more understandable --- .../frame/consumer/FileSaveFrameConsumer.java | 88 +++++++++---------- 1 file changed, 44 insertions(+), 44 deletions(-) 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 241ad8fbca..57bc312b2f 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 @@ -32,58 +32,57 @@ import org.photonvision.vision.opencv.CVMat; public class FileSaveFrameConsumer implements Consumer { + private final Logger logger = new Logger(FileSaveFrameConsumer.class, LogGroup.General); + // Formatters to generate unique, timestamped file names - private static String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString(); - private static String FILE_EXTENSION = ".jpg"; + private static final String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString(); + private static final String FILE_EXTENSION = ".jpg"; + private static final String NT_SUFFIX = "SaveImgCmd"; + DateFormat df = new SimpleDateFormat("yyyy-MM-dd"); DateFormat tf = new SimpleDateFormat("hhmmssSS"); - private final String NT_SUFFIX = "SaveImgCmd"; - private final String ntEntryName; - private NetworkTable subTable; + private final NetworkTable rootTable; - private final Logger logger; - private long imgSaveCountInternal = 0; - private String camNickname; - private String fnamePrefix; - private IntegerEntry entry; + private NetworkTable subTable; + private final String ntEntryName; + private IntegerEntry saveFrameEntry; + + private String cameraNickname; + private final String streamType; + + private long savedImagesCount = 0; public FileSaveFrameConsumer(String camNickname, String streamPrefix) { - this.fnamePrefix = camNickname + "_" + streamPrefix; this.ntEntryName = streamPrefix + NT_SUFFIX; + this.cameraNickname = camNickname; + this.streamType = streamPrefix; + this.rootTable = NetworkTablesManager.getInstance().kRootTable; updateCameraNickname(camNickname); - this.logger = new Logger(FileSaveFrameConsumer.class, this.camNickname, LogGroup.General); } public void accept(CVMat image) { if (image != null && image.getMat() != null && !image.getMat().empty()) { - var curCommand = entry.get(); // default to just our current count - if (curCommand >= 0) { - // Only do something if we got a valid current command - if (imgSaveCountInternal < curCommand) { - // Save one frame. - // Create the filename - Date now = new Date(); - String savefile = - FILE_PATH - + File.separator - + fnamePrefix - + "_" - + df.format(now) - + "T" - + tf.format(now) - + FILE_EXTENSION; - - // write to file - Imgcodecs.imwrite(savefile, image.getMat()); - - // Count one more image saved - imgSaveCountInternal++; - logger.info("Saved new image at " + savefile); - - } else if (imgSaveCountInternal > curCommand) { - imgSaveCountInternal = curCommand; - } + long currentCount = saveFrameEntry.get(); + + // Await save request + if (currentCount == -1) return; + + // The requested count is greater than the actual count + if (savedImagesCount < currentCount) { + Date now = new Date(); + + String fileName = + cameraNickname + "_" + streamType + "_" + df.format(now) + "T" + tf.format(now); + String saveFilePath = FILE_PATH + File.separator + fileName + FILE_EXTENSION; + + Imgcodecs.imwrite(saveFilePath, image.getMat()); + + savedImagesCount++; + logger.info("Saved new image at " + saveFilePath); + } else if (savedImagesCount > currentCount) { + // Reset local value with NT value in case of de-sync + savedImagesCount = currentCount; } } } @@ -97,13 +96,14 @@ public void updateCameraNickname(String newCameraNickname) { } // Recreate and re-init network tables structure - this.camNickname = newCameraNickname; - this.subTable = rootTable.getSubTable(this.camNickname); - this.subTable.getEntry(ntEntryName).setInteger(imgSaveCountInternal); - this.entry = subTable.getIntegerTopic(ntEntryName).getEntry(-1); // Default negative + this.cameraNickname = newCameraNickname; + this.subTable = rootTable.getSubTable(this.cameraNickname); + this.subTable.getEntry(ntEntryName).setInteger(savedImagesCount); + this.saveFrameEntry = subTable.getIntegerTopic(ntEntryName).getEntry(-1); // Default negative } public void overrideTakeSnapshot() { - entry.set(entry.get() + 1); + // Simulate NT change + saveFrameEntry.set(saveFrameEntry.get() + 1); } }