001/*
002 * MIT License
003 *
004 * Copyright (c) PhotonVision
005 *
006 * Permission is hereby granted, free of charge, to any person obtaining a copy
007 * of this software and associated documentation files (the "Software"), to deal
008 * in the Software without restriction, including without limitation the rights
009 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
010 * copies of the Software, and to permit persons to whom the Software is
011 * furnished to do so, subject to the following conditions:
012 *
013 * The above copyright notice and this permission notice shall be included in all
014 * copies or substantial portions of the Software.
015 *
016 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
017 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
018 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
019 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
020 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
021 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
022 * SOFTWARE.
023 */
024
025package org.photonvision;
026
027import java.util.ArrayList;
028import java.util.Arrays;
029import java.util.List;
030import java.util.Optional;
031import org.opencv.core.Core;
032import org.photonvision.common.hardware.VisionLEDMode;
033import org.photonvision.common.networktables.PacketSubscriber;
034import org.photonvision.targeting.PhotonPipelineResult;
035import org.photonvision.timesync.TimeSyncSingleton;
036import org.wpilib.driverstation.Alert;
037import org.wpilib.driverstation.DriverStationErrors;
038import org.wpilib.hardware.hal.HAL;
039import org.wpilib.math.linalg.MatBuilder;
040import org.wpilib.math.linalg.Matrix;
041import org.wpilib.math.numbers.*;
042import org.wpilib.math.util.Nat;
043import org.wpilib.networktables.BooleanPublisher;
044import org.wpilib.networktables.BooleanSubscriber;
045import org.wpilib.networktables.DoubleArraySubscriber;
046import org.wpilib.networktables.IntegerEntry;
047import org.wpilib.networktables.IntegerPublisher;
048import org.wpilib.networktables.IntegerSubscriber;
049import org.wpilib.networktables.MultiSubscriber;
050import org.wpilib.networktables.NetworkTable;
051import org.wpilib.networktables.NetworkTableInstance;
052import org.wpilib.networktables.PubSubOption;
053import org.wpilib.networktables.StringSubscriber;
054import org.wpilib.system.Timer;
055
056/** Represents a camera that is connected to PhotonVision. */
057public class PhotonCamera implements AutoCloseable {
058    private static int InstanceCount = 1;
059    public static final String kTableName = "photonvision";
060    private static final String PHOTON_ALERT_GROUP = "PhotonAlerts";
061
062    private final NetworkTable cameraTable;
063    PacketSubscriber<PhotonPipelineResult> resultSubscriber;
064    BooleanPublisher driverModePublisher;
065    BooleanSubscriber driverModeSubscriber;
066    IntegerPublisher fpsLimitPublisher;
067    IntegerSubscriber fpsLimitSubscriber;
068    BooleanSubscriber enabledSubscriber;
069    BooleanPublisher enabledPublisher;
070    StringSubscriber versionEntry;
071    IntegerEntry inputSaveImgEntry, outputSaveImgEntry;
072    IntegerPublisher pipelineIndexRequest, ledModeRequest;
073    IntegerSubscriber pipelineIndexState, ledModeState;
074    IntegerSubscriber heartbeatSubscriber;
075    DoubleArraySubscriber cameraIntrinsicsSubscriber;
076    DoubleArraySubscriber cameraDistortionSubscriber;
077    MultiSubscriber topicNameSubscriber;
078    NetworkTable rootPhotonTable;
079
080    @Override
081    public void close() {
082        resultSubscriber.close();
083        driverModePublisher.close();
084        driverModeSubscriber.close();
085        fpsLimitPublisher.close();
086        fpsLimitSubscriber.close();
087        enabledPublisher.close();
088        enabledSubscriber.close();
089        versionEntry.close();
090        inputSaveImgEntry.close();
091        outputSaveImgEntry.close();
092        pipelineIndexRequest.close();
093        pipelineIndexState.close();
094        ledModeRequest.close();
095        ledModeState.close();
096        pipelineIndexRequest.close();
097        cameraIntrinsicsSubscriber.close();
098        cameraDistortionSubscriber.close();
099        topicNameSubscriber.close();
100    }
101
102    private final String path;
103    private final String name;
104
105    private static boolean VERSION_CHECK_ENABLED = true;
106    private static long VERSION_CHECK_INTERVAL = 5;
107    double lastVersionCheckTime = 0;
108
109    private long prevHeartbeatValue = -1;
110    private double prevHeartbeatChangeTime = 0;
111    private static final double HEARTBEAT_DEBOUNCE_SEC = 0.5;
112
113    double prevTimeSyncWarnTime = 0;
114    private static final double WARN_DEBOUNCE_SEC = 5;
115
116    private final Alert disconnectAlert;
117    private final Alert timesyncAlert;
118
119    /**
120     * Sets whether or not coprocessor version checks will occur. Setting this to true will silence
121     * all console warnings about coproccessor connection, so be careful when enabling this and ensure
122     * all your coprocessors are communicating to the robot properly and everything has matching
123     * versions.
124     *
125     * @param enabled Whether or not to enable coprocessor version checks
126     */
127    public static void setVersionCheckEnabled(boolean enabled) {
128        VERSION_CHECK_ENABLED = enabled;
129    }
130
131    /**
132     * Constructs a PhotonCamera from a root table.
133     *
134     * @param instance The NetworkTableInstance to pull data from. This can be a custom instance in
135     *     simulation, but should *usually* be the default NTInstance from
136     *     NetworkTableInstance::getDefault
137     * @param cameraName The name of the camera, as seen in the UI.
138     */
139    public PhotonCamera(NetworkTableInstance instance, String cameraName) {
140        name = cameraName;
141        disconnectAlert =
142                new Alert(
143                        PHOTON_ALERT_GROUP, "PhotonCamera '" + name + "' is disconnected.", Alert.Level.MEDIUM);
144        timesyncAlert = new Alert(PHOTON_ALERT_GROUP, "", Alert.Level.MEDIUM);
145        rootPhotonTable = instance.getTable(kTableName);
146        this.cameraTable = rootPhotonTable.getSubTable(cameraName);
147        path = cameraTable.getPath();
148        var rawBytesEntry =
149                cameraTable
150                        .getRawTopic("rawBytes")
151                        .subscribe(
152                                PhotonPipelineResult.photonStruct.getTypeString(),
153                                new byte[0],
154                                PubSubOption.periodic(0.01),
155                                PubSubOption.SEND_ALL,
156                                PubSubOption.pollStorage(20));
157        resultSubscriber = new PacketSubscriber<>(rawBytesEntry, PhotonPipelineResult.photonStruct);
158        driverModePublisher = cameraTable.getBooleanTopic("driverModeRequest").publish();
159        driverModeSubscriber = cameraTable.getBooleanTopic("driverMode").subscribe(false);
160        fpsLimitPublisher = cameraTable.getIntegerTopic("fpsLimitRequest").publish();
161        fpsLimitSubscriber = cameraTable.getIntegerTopic("fpsLimit").subscribe(-1);
162        enabledPublisher = cameraTable.getBooleanTopic("enabledRequest").publish();
163        enabledSubscriber = cameraTable.getBooleanTopic("enabled").subscribe(true);
164        inputSaveImgEntry = cameraTable.getIntegerTopic("inputSaveImgCmd").getEntry(0);
165        outputSaveImgEntry = cameraTable.getIntegerTopic("outputSaveImgCmd").getEntry(0);
166        pipelineIndexRequest = cameraTable.getIntegerTopic("pipelineIndexRequest").publish();
167        pipelineIndexState = cameraTable.getIntegerTopic("pipelineIndexState").subscribe(0);
168        heartbeatSubscriber = cameraTable.getIntegerTopic("heartbeat").subscribe(-1);
169        cameraIntrinsicsSubscriber =
170                cameraTable.getDoubleArrayTopic("cameraIntrinsics").subscribe(null);
171        cameraDistortionSubscriber =
172                cameraTable.getDoubleArrayTopic("cameraDistortion").subscribe(null);
173
174        ledModeRequest = rootPhotonTable.getIntegerTopic("ledModeRequest").publish();
175        ledModeState = rootPhotonTable.getIntegerTopic("ledModeState").subscribe(-1);
176        versionEntry = rootPhotonTable.getStringTopic("version").subscribe("");
177
178        // Existing is enough to make this multisubscriber do its thing
179        topicNameSubscriber =
180                new MultiSubscriber(instance, new String[] {"/photonvision/"}, PubSubOption.TOPICS_ONLY);
181
182        InstanceCount++;
183        HAL.reportUsage("PhotonVision/PhotonCamera", InstanceCount, "");
184
185        // HACK - start a TimeSyncServer, if we haven't yet.
186        TimeSyncSingleton.load();
187
188        // HACK - check if things are compatible
189        verifyDependencies();
190    }
191
192    /** This is something we only need to check for java because of the way java packages opencv. */
193    static void verifyDependencies() {
194        // spotless:off
195        // WPILIB names their opencv version in the format YEAR-OPENCVVERSION-PATCH
196        // so we split on '-' and take the middle part to get the version number
197        if (!Core.VERSION.equals(PhotonVersion.opencvTargetVersion.split("-")[1])) {
198            String bfw = """
199
200
201
202
203                    >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\s
204                    >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\s
205                    >>>                                          \s
206                    >>> You are running an incompatible version  \s
207                    >>> of PhotonVision !                        \s
208                    >>>                                          \s
209                    >>> PhotonLib """
210                    + PhotonVersion.versionString
211                    + " is built for OpenCV "
212                    + PhotonVersion.opencvTargetVersion
213                    + "\n"
214                    + ">>> but you are using OpenCV "
215                    + Core.VERSION
216                    + """
217                    \n>>>                                          \s
218                    >>> This is neither tested nor supported.    \s
219                    >>> You MUST update WPILib, PhotonLib, or both.
220                    >>> Check `./gradlew dependencies` and ensure\s
221                    >>> all mentions of OpenCV match the version \s
222                    >>> that PhotonLib was built for. If you find a
223                    >>> a mismatched version in a dependency, you\s
224                    >>> must take steps to update the version of \s
225                    >>> OpenCV used in that dependency. If you do\s
226                    >>> not control that dependency and an updated\s
227                    >>> version is not available, contact the    \s
228                    >>> developers of that dependency.           \s
229                    >>>                                          \s
230                    >>> Your code will now crash.                \s
231                    >>> We hope your day gets better.            \s
232                    >>>                                          \s
233                    >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\s
234                    >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\s
235                    """;
236            // spotless:on
237
238            DriverStationErrors.reportWarning(bfw, false);
239            DriverStationErrors.reportError(bfw, false);
240            throw new UnsupportedOperationException(bfw);
241        }
242    }
243
244    /**
245     * Constructs a PhotonCamera from the name of the camera.
246     *
247     * @param cameraName The nickname of the camera (found in the PhotonVision UI).
248     */
249    public PhotonCamera(String cameraName) {
250        this(NetworkTableInstance.getDefault(), cameraName);
251    }
252
253    /**
254     * The list of pipeline results sent by PhotonVision since the last call to getAllUnreadResults().
255     * Calling this function clears the internal FIFO queue, and multiple calls to
256     * getAllUnreadResults() will return different (potentially empty) result arrays. Be careful to
257     * call this exactly ONCE per loop of your robot code! FIFO depth is limited to 20 changes, so
258     * make sure to call this frequently enough to avoid old results being discarded, too!
259     *
260     * @return The list of pipeline results
261     */
262    public List<PhotonPipelineResult> getAllUnreadResults() {
263        verifyVersion();
264        updateDisconnectAlert();
265
266        // Grab the latest results. We don't care about the timestamps from NT - the metadata header has
267        // this, latency compensated by the Time Sync Client
268        var changes = resultSubscriber.getAllChanges();
269        List<PhotonPipelineResult> ret = new ArrayList<>(changes.size());
270        for (var c : changes) {
271            var result = c.value;
272            checkTimeSyncOrWarn(result);
273            ret.add(result);
274        }
275
276        return ret;
277    }
278
279    /**
280     * Returns the latest pipeline result. This is simply the most recent result Received via NT.
281     * Calling this multiple times will always return the most recent result.
282     *
283     * <p>Replaced by {@link #getAllUnreadResults()} over getLatestResult, as this function can miss
284     * results, or provide duplicate ones!
285     *
286     * @return The latest pipeline result
287     */
288    @Deprecated(since = "2024", forRemoval = true)
289    public PhotonPipelineResult getLatestResult() {
290        verifyVersion();
291        updateDisconnectAlert();
292
293        // Grab the latest result. We don't care about the timestamp from NT - the metadata header has
294        // this, latency compensated by the Time Sync Client
295        var ret = resultSubscriber.get();
296
297        if (ret.timestamp == 0) return new PhotonPipelineResult();
298
299        var result = ret.value;
300
301        checkTimeSyncOrWarn(result);
302
303        return result;
304    }
305
306    private void updateDisconnectAlert() {
307        disconnectAlert.set(!isConnected());
308    }
309
310    private void checkTimeSyncOrWarn(PhotonPipelineResult result) {
311        if (result.metadata.timeSinceLastPong > 5L * 1000000L) {
312            String warningText =
313                    "PhotonVision coprocessor at path "
314                            + path
315                            + " is not connected to the TimeSyncServer? It's been "
316                            + String.format("%.2f", result.metadata.timeSinceLastPong / 1e6)
317                            + "s since the coprocessor last heard a pong.";
318
319            timesyncAlert.setText(warningText);
320            timesyncAlert.set(true);
321
322            if (Timer.getMonotonicTimestamp() > (prevTimeSyncWarnTime + WARN_DEBOUNCE_SEC)) {
323                prevTimeSyncWarnTime = Timer.getMonotonicTimestamp();
324
325                DriverStationErrors.reportWarning(
326                        warningText
327                                + "\n\nCheck /photonvision/.timesync/{COPROCESSOR_HOSTNAME} for more information.",
328                        false);
329            }
330        } else {
331            // Got a valid packet, reset the last time
332            prevTimeSyncWarnTime = 0;
333            timesyncAlert.set(false);
334        }
335    }
336
337    /**
338     * Returns whether the camera is in driver mode.
339     *
340     * @return Whether the camera is in driver mode.
341     */
342    public boolean getDriverMode() {
343        return driverModeSubscriber.get();
344    }
345
346    /**
347     * Toggles driver mode.
348     *
349     * @param driverMode Whether to set driver mode.
350     */
351    public void setDriverMode(boolean driverMode) {
352        driverModePublisher.set(driverMode);
353    }
354
355    /**
356     * @return The current FPS limit.
357     */
358    public int getFPSLimit() {
359        return (int) fpsLimitSubscriber.get();
360    }
361
362    /**
363     * Sets the FPS limit on the camera.
364     *
365     * <p>A negative FPS limit is treated as no FPS limit, and will run as fast as possible.
366     *
367     * <p>Otherwise, will limit processing to at most the provided FPS limit
368     *
369     * @param fps The FPS limit to set.
370     */
371    public void setFPSLimit(int fps) {
372        fpsLimitPublisher.set(fps);
373    }
374
375    /**
376     * Sets whether the camera is enabled, default is true.
377     *
378     * @param enabled Whether to enable the camera.
379     */
380    public void setEnabled(boolean enabled) {
381        enabledPublisher.set(enabled);
382    }
383
384    /**
385     * @return Whether the camera is enabled.
386     */
387    public boolean getEnabled() {
388        return enabledSubscriber.get();
389    }
390
391    /**
392     * Request the camera to save a new image file from the input camera stream with overlays. Images
393     * take up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk
394     * space and eventually cause the system to stop working. Clear out images in
395     * /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues.
396     */
397    public void takeInputSnapshot() {
398        inputSaveImgEntry.set(inputSaveImgEntry.get() + 1);
399    }
400
401    /**
402     * Request the camera to save a new image file from the output stream with overlays. Images take
403     * up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk space
404     * and eventually cause the system to stop working. Clear out images in
405     * /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues.
406     */
407    public void takeOutputSnapshot() {
408        outputSaveImgEntry.set(outputSaveImgEntry.get() + 1);
409    }
410
411    /**
412     * Returns the active pipeline index.
413     *
414     * @return The active pipeline index.
415     */
416    public int getPipelineIndex() {
417        return (int) pipelineIndexState.get(0);
418    }
419
420    /**
421     * Allows the user to select the active pipeline index.
422     *
423     * @param index The active pipeline index.
424     */
425    public void setPipelineIndex(int index) {
426        pipelineIndexRequest.set(index);
427    }
428
429    /**
430     * Returns the current LED mode.
431     *
432     * @return The current LED mode.
433     */
434    public VisionLEDMode getLEDMode() {
435        int value = (int) ledModeState.get(-1);
436        return switch (value) {
437            case 0 -> VisionLEDMode.kOff;
438            case 1 -> VisionLEDMode.kOn;
439            case 2 -> VisionLEDMode.kBlink;
440            default -> VisionLEDMode.kDefault;
441        };
442    }
443
444    /**
445     * Sets the LED mode.
446     *
447     * @param led The mode to set to.
448     */
449    public void setLED(VisionLEDMode led) {
450        ledModeRequest.set(led.value);
451    }
452
453    /**
454     * Returns the name of the camera. This will return the same value that was given to the
455     * constructor as cameraName.
456     *
457     * @return The name of the camera.
458     */
459    public String getName() {
460        return name;
461    }
462
463    /**
464     * Returns whether the camera is connected and actively returning new data. Connection status is
465     * debounced.
466     *
467     * @return True if the camera is actively sending frame data, false otherwise.
468     */
469    public boolean isConnected() {
470        var curHeartbeat = heartbeatSubscriber.get();
471        var now = Timer.getMonotonicTimestamp();
472
473        if (curHeartbeat < 0) {
474            // we have never heard from the camera
475            return false;
476        }
477
478        if (curHeartbeat != prevHeartbeatValue) {
479            // New heartbeat value from the coprocessor
480            prevHeartbeatChangeTime = now;
481            prevHeartbeatValue = curHeartbeat;
482        }
483
484        return (now - prevHeartbeatChangeTime) < HEARTBEAT_DEBOUNCE_SEC;
485    }
486
487    public Optional<Matrix<N3, N3>> getCameraMatrix() {
488        var cameraMatrix = cameraIntrinsicsSubscriber.get();
489        if (cameraMatrix != null && cameraMatrix.length == 9) {
490            return Optional.of(MatBuilder.fill(Nat.N3(), Nat.N3(), cameraMatrix));
491        } else return Optional.empty();
492    }
493
494    /**
495     * Returns the camera calibration's distortion coefficients, in OPENCV8 form. Higher-order terms
496     * are set to 0
497     *
498     * @return The distortion coefficients in a 8x1 matrix, if they are published by the camera. Empty
499     *     otherwise.
500     */
501    public Optional<Matrix<N8, N1>> getDistCoeffs() {
502        var distCoeffs = cameraDistortionSubscriber.get();
503        if (distCoeffs != null && distCoeffs.length <= 8) {
504            // Copy into array of length 8, and explicitly null higher order terms out
505            double[] data = new double[8];
506            Arrays.fill(data, 0);
507            System.arraycopy(distCoeffs, 0, data, 0, distCoeffs.length);
508
509            return Optional.of(MatBuilder.fill(Nat.N8(), Nat.N1(), data));
510        } else return Optional.empty();
511    }
512
513    /**
514     * Gets the NetworkTable representing this camera's subtable. You probably don't ever need to call
515     * this.
516     */
517    public final NetworkTable getCameraTable() {
518        return cameraTable;
519    }
520
521    void verifyVersion() {
522        if (!VERSION_CHECK_ENABLED) return;
523
524        if ((Timer.getMonotonicTimestamp() - lastVersionCheckTime) < VERSION_CHECK_INTERVAL) return;
525        lastVersionCheckTime = Timer.getMonotonicTimestamp();
526
527        // Heartbeat entry is assumed to always be present. If it's not present, we
528        // assume that a camera with that name was never connected in the first place.
529        if (!heartbeatSubscriber.exists()) {
530            var cameraNames = getTablesThatLookLikePhotonCameras();
531            if (cameraNames.isEmpty()) {
532                DriverStationErrors.reportError(
533                        "Could not find **any** PhotonVision coprocessors on NetworkTables. Double check that PhotonVision is running, and that your camera is connected!",
534                        false);
535            } else {
536                DriverStationErrors.reportError(
537                        "PhotonVision coprocessor at path "
538                                + path
539                                + " not found on NetworkTables. Double check that your camera names match!",
540                        true);
541
542                var cameraNameStr = new StringBuilder();
543                for (var c : cameraNames) {
544                    cameraNameStr.append(" ==> ");
545                    cameraNameStr.append(c);
546                    cameraNameStr.append("\n");
547                }
548
549                DriverStationErrors.reportError(
550                        "Found the following PhotonVision cameras on NetworkTables:\n"
551                                + cameraNameStr.toString(),
552                        false);
553            }
554        }
555        // Check for connection status. Warn if disconnected.
556        else if (!isConnected()) {
557            DriverStationErrors.reportWarning(
558                    "PhotonVision coprocessor at path " + path + " is not sending new data.", false);
559        }
560
561        String versionString = versionEntry.get("");
562
563        // Check mdef UUID
564        String local_uuid = PhotonPipelineResult.photonStruct.getInterfaceUUID();
565        String remote_uuid = resultSubscriber.getInterfaceUUID();
566
567        if (remote_uuid == null || remote_uuid.isEmpty()) {
568            // not connected yet?
569            DriverStationErrors.reportWarning(
570                    "PhotonVision coprocessor at path "
571                            + path
572                            + " has not reported a message interface UUID - is your coprocessor's camera started?",
573                    false);
574        } else if (!local_uuid.equals(remote_uuid)) {
575            // Error on a verified version mismatch
576            // But stay silent otherwise
577
578            // spotless:off
579            String bfw = """
580
581
582
583
584
585                    >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>
586                    >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
587                    >>>                                         \s
588                    >>> You are running an incompatible version \s
589                    >>> of PhotonVision on your coprocessor!    \s
590                    >>>                                         \s
591                    >>> This is neither tested nor supported.   \s
592                    >>> You MUST update PhotonVision,           \s
593                    >>> PhotonLib, or both.                     \s
594                    >>>                                         \s
595                    >>> Your code will now crash.               \s
596                    >>> We hope your day gets better.           \s
597                    >>>                                         \s
598                    >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
599                    >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>
600                    """;
601            // spotless:on
602
603            DriverStationErrors.reportWarning(bfw, false);
604            String versionMismatchMessage =
605                    "Photon version "
606                            + PhotonVersion.versionString
607                            + " (message definition version "
608                            + local_uuid
609                            + ")"
610                            + " does not match coprocessor version "
611                            + versionString
612                            + " (message definition version "
613                            + remote_uuid
614                            + ")"
615                            + "!";
616            DriverStationErrors.reportError(versionMismatchMessage, false);
617            throw new UnsupportedOperationException(versionMismatchMessage);
618        }
619    }
620
621    private List<String> getTablesThatLookLikePhotonCameras() {
622        return rootPhotonTable.getSubTables().stream()
623                .filter(
624                        it -> {
625                            return rootPhotonTable.getSubTable(it).getEntry("rawBytes").exists();
626                        })
627                .toList();
628    }
629}