diff --git a/photon-lib/py/photonlibpy/photonCamera.py b/photon-lib/py/photonlibpy/photonCamera.py index 512e3633bd..e4b35b4083 100644 --- a/photon-lib/py/photonlibpy/photonCamera.py +++ b/photon-lib/py/photonlibpy/photonCamera.py @@ -18,6 +18,7 @@ from enum import Enum from typing import List +import hal import ntcore # magical import to make serde stuff work @@ -48,6 +49,8 @@ def setVersionCheckEnabled(enabled: bool): class PhotonCamera: + instance_count = 1 + def __init__(self, cameraName: str): """Constructs a PhotonCamera from the name of the camera. @@ -108,6 +111,13 @@ def __init__(self, cameraName: str): # Start the time sync server inst.start() + # Usage reporting + hal.report( + hal.tResourceType.kResourceType_PhotonCamera.value, + PhotonCamera.instance_count, + ) + PhotonCamera.instance_count += 1 + def getAllUnreadResults(self) -> List[PhotonPipelineResult]: """ The list of pipeline results sent by PhotonVision since the last call to getAllUnreadResults(). diff --git a/photon-lib/py/photonlibpy/photonPoseEstimator.py b/photon-lib/py/photonlibpy/photonPoseEstimator.py index 201d1da2b2..a1b0c881e1 100644 --- a/photon-lib/py/photonlibpy/photonPoseEstimator.py +++ b/photon-lib/py/photonlibpy/photonPoseEstimator.py @@ -18,6 +18,7 @@ import enum from typing import Optional +import hal import wpilib from robotpy_apriltag import AprilTagFieldLayout from wpimath.geometry import Pose2d, Pose3d, Transform3d @@ -61,6 +62,8 @@ class PoseStrategy(enum.Enum): class PhotonPoseEstimator: + instance_count = 1 + """ The PhotonPoseEstimator class filters or combines readings from all the AprilTags visible at a given timestamp on the field to produce a single robot in field pose, using the strategy set @@ -96,7 +99,12 @@ def __init__( self._lastPose: Optional[Pose3d] = None self._referencePose: Optional[Pose3d] = None - # TODO: Implement HAL reporting + # Usage reporting + hal.report( + hal.tResourceType.kResourceType_PhotonPoseEstimator.value, + PhotonPoseEstimator.instance_count, + ) + PhotonPoseEstimator.instance_count += 1 @property def fieldTags(self) -> AprilTagFieldLayout: diff --git a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java index 198c387323..eb2772adf8 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java @@ -58,7 +58,7 @@ /** Represents a camera that is connected to PhotonVision. */ public class PhotonCamera implements AutoCloseable { - private static int InstanceCount = 0; + private static int InstanceCount = 1; public static final String kTableName = "photonvision"; private static final String PHOTON_ALERT_GROUP = "PhotonAlerts"; diff --git a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java index 1675ad3d1a..fc61fe91a8 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java @@ -58,7 +58,7 @@ * below. Example usage can be found in our apriltagExample example project. */ public class PhotonPoseEstimator { - private static int InstanceCount = 0; + private static int InstanceCount = 1; /** Position estimation strategies that can be used by the {@link PhotonPoseEstimator} class. */ public enum PoseStrategy { diff --git a/photon-lib/src/main/native/include/photon/PhotonCamera.h b/photon-lib/src/main/native/include/photon/PhotonCamera.h index 66f6e1276f..5281bbe747 100644 --- a/photon-lib/src/main/native/include/photon/PhotonCamera.h +++ b/photon-lib/src/main/native/include/photon/PhotonCamera.h @@ -225,7 +225,7 @@ class PhotonCamera { private: units::second_t lastVersionCheckTime = 0_s; static bool VERSION_CHECK_ENABLED; - inline static int InstanceCount = 0; + inline static int InstanceCount = 1; units::second_t prevTimeSyncWarnTime = 0_s; diff --git a/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h b/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h index 7b129a666e..a20ea775ca 100644 --- a/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h +++ b/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h @@ -200,7 +200,7 @@ class PhotonPoseEstimator { units::second_t poseCacheTimestamp; - inline static int InstanceCount = 0; + inline static int InstanceCount = 1; inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }