From 918c3b98d7fcbac2aa262bdae88f009de6148026 Mon Sep 17 00:00:00 2001 From: Sriman Achanta <68172138+srimanachanta@users.noreply.github.com> Date: Sat, 16 Dec 2023 14:02:52 -0500 Subject: [PATCH] report cpp usage --- .../src/main/native/cpp/photon/PhotonCamera.cpp | 7 ++++++- .../main/native/cpp/photon/PhotonPoseEstimator.cpp | 14 ++++++++++++-- .../src/main/native/include/photon/PhotonCamera.h | 1 + .../native/include/photon/PhotonPoseEstimator.h | 2 ++ 4 files changed, 21 insertions(+), 3 deletions(-) diff --git a/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp b/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp index ff26f74fb8..02d9b46527 100644 --- a/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp +++ b/photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp @@ -24,6 +24,8 @@ #include "photon/PhotonCamera.h" +#include + #include #include #include @@ -69,7 +71,10 @@ PhotonCamera::PhotonCamera(nt::NetworkTableInstance instance, rootTable->GetBooleanTopic("driverModeRequest").Publish()), m_topicNameSubscriber(instance, PHOTON_PREFIX, {.topicsOnly = true}), path(rootTable->GetPath()), - m_cameraName(cameraName) {} + m_cameraName(cameraName) { + HAL_Report(HALUsageReporting::kResourceType_PhotonCamera, InstanceCount); + InstanceCount++; +} PhotonCamera::PhotonCamera(const std::string_view cameraName) : PhotonCamera(nt::NetworkTableInstance::GetDefault(), cameraName) {} diff --git a/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp b/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp index f2ff30f7ea..30bc6de2df 100644 --- a/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp +++ b/photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp @@ -24,6 +24,8 @@ #include "photon/PhotonPoseEstimator.h" +#include + #include #include #include @@ -68,7 +70,11 @@ PhotonPoseEstimator::PhotonPoseEstimator(frc::AprilTagFieldLayout tags, m_robotToCamera(robotToCamera), lastPose(frc::Pose3d()), referencePose(frc::Pose3d()), - poseCacheTimestamp(-1_s) {} + poseCacheTimestamp(-1_s) { + HAL_Report(HALUsageReporting::kResourceType_PhotonPoseEstimator, + InstanceCount); + InstanceCount++; +} PhotonPoseEstimator::PhotonPoseEstimator(frc::AprilTagFieldLayout tags, PoseStrategy strat, PhotonCamera&& cam, @@ -79,7 +85,11 @@ PhotonPoseEstimator::PhotonPoseEstimator(frc::AprilTagFieldLayout tags, m_robotToCamera(robotToCamera), lastPose(frc::Pose3d()), referencePose(frc::Pose3d()), - poseCacheTimestamp(-1_s) {} + poseCacheTimestamp(-1_s) { + HAL_Report(HALUsageReporting::kResourceType_PhotonPoseEstimator, + InstanceCount); + InstanceCount++; +} void PhotonPoseEstimator::SetMultiTagFallbackStrategy(PoseStrategy strategy) { if (strategy == MULTI_TAG_PNP_ON_COPROCESSOR || diff --git a/photon-lib/src/main/native/include/photon/PhotonCamera.h b/photon-lib/src/main/native/include/photon/PhotonCamera.h index 582458e014..99aa52c61b 100644 --- a/photon-lib/src/main/native/include/photon/PhotonCamera.h +++ b/photon-lib/src/main/native/include/photon/PhotonCamera.h @@ -205,6 +205,7 @@ class PhotonCamera { private: units::second_t lastVersionCheckTime = 0_s; inline static bool VERSION_CHECK_ENABLED = true; + inline static int InstanceCount = 0; void VerifyVersion(); }; diff --git a/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h b/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h index cdb60f6cee..2c863330bb 100644 --- a/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h +++ b/photon-lib/src/main/native/include/photon/PhotonPoseEstimator.h @@ -231,6 +231,8 @@ class PhotonPoseEstimator { units::second_t poseCacheTimestamp; + inline static int InstanceCount = 0; + inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; } std::optional Update(