Skip to content

Commit

Permalink
Report cpp usage (PhotonVision#1045)
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta authored and crschardt committed Dec 18, 2023
1 parent d5541a5 commit 9b29722
Show file tree
Hide file tree
Showing 4 changed files with 21 additions and 3 deletions.
7 changes: 6 additions & 1 deletion photon-lib/src/main/native/cpp/photon/PhotonCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@

#include "photon/PhotonCamera.h"

#include <hal/FRCUsageReporting.h>

#include <frc/Errors.h>
#include <frc/Timer.h>
#include <opencv2/core.hpp>
Expand Down Expand Up @@ -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) {}
Expand Down
14 changes: 12 additions & 2 deletions photon-lib/src/main/native/cpp/photon/PhotonPoseEstimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@

#include "photon/PhotonPoseEstimator.h"

#include <hal/FRCUsageReporting.h>

#include <cmath>
#include <iostream>
#include <limits>
Expand Down Expand Up @@ -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,
Expand All @@ -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 ||
Expand Down
1 change: 1 addition & 0 deletions photon-lib/src/main/native/include/photon/PhotonCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -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();
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -231,6 +231,8 @@ class PhotonPoseEstimator {

units::second_t poseCacheTimestamp;

inline static int InstanceCount = 0;

inline void InvalidatePoseCache() { poseCacheTimestamp = -1_s; }

std::optional<EstimatedRobotPose> Update(
Expand Down

0 comments on commit 9b29722

Please sign in to comment.