Skip to content

Commit

Permalink
[choreolib] Add usage reporting (#963)
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul authored Dec 2, 2024
1 parent ee7d531 commit c0dd437
Show file tree
Hide file tree
Showing 5 changed files with 21 additions and 0 deletions.
1 change: 1 addition & 0 deletions .styleguide
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ includeOtherLibs {
^frc/
^frc2/
^gtest/
^hal/
^units/
^wpi/
}
1 change: 1 addition & 0 deletions choreolib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ dependencies {
implementation 'edu.wpi.first.wpiunits:wpiunits-java:2025.+'
implementation 'edu.wpi.first.ntcore:ntcore-java:2025.+'
implementation 'edu.wpi.first.ntcore:ntcore-jni:2025.+'
implementation 'edu.wpi.first.hal:hal-java:2025.+'

api "com.fasterxml.jackson.core:jackson-annotations:2.15.2"
api "com.fasterxml.jackson.core:jackson-core:2.15.2"
Expand Down
6 changes: 6 additions & 0 deletions choreolib/src/main/java/choreo/Choreo.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
import com.google.gson.GsonBuilder;
import com.google.gson.JsonObject;
import com.google.gson.JsonSyntaxException;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Filesystem;
Expand Down Expand Up @@ -182,9 +184,13 @@ static Trajectory<? extends TrajectorySample<?>> loadTrajectoryString(
splits = newArray;
}
if (projectFile.type.equals("Swerve")) {
HAL.report(tResourceType.kResourceType_ChoreoTrajectory, 1);

SwerveSample[] samples = GSON.fromJson(trajectoryObj.get("samples"), SwerveSample[].class);
return new Trajectory<SwerveSample>(name, List.of(samples), List.of(splits), List.of(events));
} else if (projectFile.type.equals("Differential")) {
HAL.report(tResourceType.kResourceType_ChoreoTrajectory, 2);

DifferentialSample[] sampleArray =
GSON.fromJson(trajectoryObj.get("samples"), DifferentialSample[].class);
return new Trajectory<DifferentialSample>(
Expand Down
3 changes: 3 additions & 0 deletions choreolib/src/main/java/choreo/auto/AutoFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
import choreo.trajectory.SwerveSample;
import choreo.trajectory.Trajectory;
import choreo.trajectory.TrajectorySample;
import edu.wpi.first.hal.FRCNetComm.tResourceType;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;
Expand Down Expand Up @@ -125,6 +127,7 @@ public <SampleType extends TrajectorySample<SampleType>> AutoFactory(
this.bindings.merge(bindings);
this.trajectoryLogger =
trajectoryLogger.map(logger -> (TrajectoryLogger<? extends TrajectorySample<?>>) logger);
HAL.report(tResourceType.kResourceType_ChoreoTrigger, 1);
}

/**
Expand Down
10 changes: 10 additions & 0 deletions choreolib/src/main/native/include/choreo/Choreo.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#pragma once

#include <concepts>
#include <functional>
#include <optional>
#include <string>
Expand All @@ -14,10 +15,13 @@
#include <frc/Filesystem.h>
#include <frc/geometry/Pose2d.h>
#include <frc2/command/Subsystem.h>
#include <hal/FRCUsageReporting.h>
#include <wpi/MemoryBuffer.h>
#include <wpi/json.h>

#include "choreo/trajectory/DifferentialSample.h"
#include "choreo/trajectory/ProjectFile.h"
#include "choreo/trajectory/SwerveSample.h"
#include "choreo/trajectory/Trajectory.h"
#include "choreo/trajectory/TrajectorySample.h"
#include "choreo/util/AllianceFlipperUtil.h"
Expand Down Expand Up @@ -144,6 +148,12 @@ class Choreo {
template <TrajectorySample SampleType>
static std::optional<Trajectory<SampleType>> LoadTrajectoryString(
std::string_view trajectoryJsonString, std::string_view trajectoryName) {
if constexpr (std::same_as<SampleType, SwerveSample>) {
HAL_Report(HALUsageReporting::kResourceType_ChoreoTrajectory, 1);
} else if constexpr (std::same_as<SampleType, DifferentialSample>) {
HAL_Report(HALUsageReporting::kResourceType_ChoreoTrajectory, 2);
}

wpi::json json = wpi::json::parse(trajectoryJsonString);
std::string version = json["version"];
if (kSpecVersion != version) {
Expand Down

0 comments on commit c0dd437

Please sign in to comment.