Skip to content

Fix usage reporting. #1964

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 2 commits into from
Jul 1, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 10 additions & 0 deletions photon-lib/py/photonlibpy/photonCamera.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
from enum import Enum
from typing import List

import hal
import ntcore

# magical import to make serde stuff work
Expand Down Expand Up @@ -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.

Expand Down Expand Up @@ -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().
Expand Down
10 changes: 9 additions & 1 deletion photon-lib/py/photonlibpy/photonPoseEstimator.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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";

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
2 changes: 1 addition & 1 deletion photon-lib/src/main/native/include/photon/PhotonCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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; }

Expand Down
Loading