From 764ada9b662d33ced986279db6453e639e39a703 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Fri, 7 Feb 2025 12:37:23 -0800 Subject: [PATCH] [hal] Change usage reporting to string-based (#7763) --- .github/actions/pregen/action.yml | 3 - .../wpi/first/cameraserver/CameraServer.java | 10 +- .../cameraserver/CameraServerShared.java | 21 +- .../cameraserver/CameraServerSharedStore.java | 18 +- .../native/cpp/cameraserver/CameraServer.cpp | 12 +- .../cpp/cameraserver/CameraServerShared.cpp | 4 +- .../include/cameraserver/CameraServerShared.h | 6 +- .../epilogue/processor/EpilogueGenerator.java | 6 +- .../processor/EpilogueGeneratorTest.java | 30 +- hal/BUILD.bazel | 17 +- hal/CMakeLists.txt | 8 +- hal/doc/usage.adoc | 70 +++ hal/generate_usage_reporting.py | 109 ----- hal/src/generate/FRCNetComm.java.in | 38 -- hal/src/generate/FRCUsageReporting.h.in | 60 --- hal/src/generate/Instances.txt | 80 ---- hal/src/generate/ResourceType.txt | 127 ----- hal/src/generate/UsageReporting.h.in | 55 --- .../java/edu/wpi/first/hal/FRCNetComm.java | 450 ------------------ .../native/include/hal/FRCUsageReporting.h | 265 ----------- .../main/native/include/hal/UsageReporting.h | 260 ---------- .../edu/wpi/first/hal/DriverStationJNI.java | 48 -- hal/src/main/java/edu/wpi/first/hal/HAL.java | 56 +-- .../edu/wpi/first/hal/UsageReportingJNI.java | 25 + hal/src/main/native/cpp/UsageReporting.cpp | 12 + .../main/native/cpp/jni/DriverStationJNI.cpp | 17 - .../main/native/cpp/jni/UsageReportingJNI.cpp | 35 ++ hal/src/main/native/include/hal/HAL.h | 2 +- .../main/native/include/hal/UsageReporting.h | 66 +++ hal/src/main/native/sim/HAL.cpp | 4 +- hal/src/main/native/systemcore/HAL.cpp | 13 +- .../main/native/systemcore/HALInitializer.h | 1 + .../main/native/systemcore/UsageReporting.cpp | 51 ++ .../wpilibj2/command/CommandScheduler.java | 4 +- .../cpp/frc2/command/CommandScheduler.cpp | 5 +- .../generate/main/native/cpp/hid.cpp.jinja | 4 +- .../pwm_motor_controller.cpp.jinja | 4 +- .../main/native/cpp/PS4Controller.cpp | 4 +- .../main/native/cpp/PS5Controller.cpp | 4 +- .../main/native/cpp/StadiaController.cpp | 4 +- .../main/native/cpp/XboxController.cpp | 4 +- .../main/native/cpp/motorcontrol/DMC60.cpp | 4 +- .../main/native/cpp/motorcontrol/Jaguar.cpp | 4 +- .../main/native/cpp/motorcontrol/Koors40.cpp | 4 +- .../native/cpp/motorcontrol/PWMSparkFlex.cpp | 4 +- .../native/cpp/motorcontrol/PWMSparkMax.cpp | 4 +- .../native/cpp/motorcontrol/PWMTalonFX.cpp | 4 +- .../native/cpp/motorcontrol/PWMTalonSRX.cpp | 4 +- .../main/native/cpp/motorcontrol/PWMVenom.cpp | 4 +- .../native/cpp/motorcontrol/PWMVictorSPX.cpp | 4 +- .../main/native/cpp/motorcontrol/SD540.cpp | 4 +- .../main/native/cpp/motorcontrol/Spark.cpp | 4 +- .../native/cpp/motorcontrol/SparkMini.cpp | 4 +- .../main/native/cpp/motorcontrol/Talon.cpp | 4 +- .../main/native/cpp/motorcontrol/Victor.cpp | 4 +- .../main/native/cpp/motorcontrol/VictorSP.cpp | 4 +- wpilibc/src/main/native/cpp/ADXL345_I2C.cpp | 7 +- .../src/main/native/cpp/AddressableLED.cpp | 4 +- .../main/native/cpp/AnalogAccelerometer.cpp | 5 +- wpilibc/src/main/native/cpp/AnalogEncoder.cpp | 3 + wpilibc/src/main/native/cpp/AnalogInput.cpp | 4 +- wpilibc/src/main/native/cpp/CAN.cpp | 15 +- wpilibc/src/main/native/cpp/Compressor.cpp | 3 +- .../src/main/native/cpp/DataLogManager.cpp | 8 +- wpilibc/src/main/native/cpp/DigitalInput.cpp | 4 +- wpilibc/src/main/native/cpp/DigitalOutput.cpp | 4 +- .../src/main/native/cpp/DoubleSolenoid.cpp | 9 +- wpilibc/src/main/native/cpp/DutyCycle.cpp | 4 +- wpilibc/src/main/native/cpp/Encoder.cpp | 17 +- wpilibc/src/main/native/cpp/I2C.cpp | 5 +- .../main/native/cpp/IterativeRobotBase.cpp | 1 - wpilibc/src/main/native/cpp/Joystick.cpp | 4 +- wpilibc/src/main/native/cpp/Notifier.cpp | 1 - wpilibc/src/main/native/cpp/PWM.cpp | 4 +- wpilibc/src/main/native/cpp/PneumaticHub.cpp | 5 + .../native/cpp/PneumaticsControlModule.cpp | 7 + .../src/main/native/cpp/PowerDistribution.cpp | 14 +- wpilibc/src/main/native/cpp/Preferences.cpp | 4 +- wpilibc/src/main/native/cpp/SerialPort.cpp | 8 +- wpilibc/src/main/native/cpp/Servo.cpp | 4 +- wpilibc/src/main/native/cpp/SharpIR.cpp | 2 + wpilibc/src/main/native/cpp/Solenoid.cpp | 4 +- wpilibc/src/main/native/cpp/Threads.cpp | 1 - wpilibc/src/main/native/cpp/TimedRobot.cpp | 5 +- .../main/native/cpp/counter/Tachometer.cpp | 4 +- .../main/native/cpp/counter/UpDownCounter.cpp | 4 +- .../native/cpp/drive/DifferentialDrive.cpp | 11 +- .../main/native/cpp/drive/MecanumDrive.cpp | 8 +- .../main/native/cpp/drive/RobotDriveBase.cpp | 2 - .../cpp/motorcontrol/NidecBrushless.cpp | 5 +- .../cpp/smartdashboard/SmartDashboard.cpp | 8 +- wpilibc/src/main/native/cppcs/RobotBase.cpp | 129 +---- .../main/native/include/frc/PneumaticHub.h | 2 + .../main/native/include/frc/PneumaticsBase.h | 9 + .../include/frc/PneumaticsControlModule.h | 2 + .../src/main/native/include/frc/RobotBase.h | 1 - wpilibj/src/generate/hids.json | 4 - wpilibj/src/generate/hids.schema.json | 4 - wpilibj/src/generate/main/java/hid.java.jinja | 5 +- .../main/java/pwm_motor_controller.java.jinja | 3 +- .../edu/wpi/first/wpilibj/PS4Controller.java | 3 +- .../edu/wpi/first/wpilibj/PS5Controller.java | 5 +- .../wpi/first/wpilibj/StadiaController.java | 5 +- .../edu/wpi/first/wpilibj/XboxController.java | 3 +- .../wpi/first/wpilibj/motorcontrol/DMC60.java | 3 +- .../first/wpilibj/motorcontrol/Jaguar.java | 3 +- .../first/wpilibj/motorcontrol/Koors40.java | 3 +- .../wpilibj/motorcontrol/PWMSparkFlex.java | 3 +- .../wpilibj/motorcontrol/PWMSparkMax.java | 3 +- .../wpilibj/motorcontrol/PWMTalonFX.java | 3 +- .../wpilibj/motorcontrol/PWMTalonSRX.java | 3 +- .../first/wpilibj/motorcontrol/PWMVenom.java | 3 +- .../wpilibj/motorcontrol/PWMVictorSPX.java | 3 +- .../wpi/first/wpilibj/motorcontrol/SD540.java | 3 +- .../wpi/first/wpilibj/motorcontrol/Spark.java | 3 +- .../first/wpilibj/motorcontrol/SparkMini.java | 3 +- .../wpi/first/wpilibj/motorcontrol/Talon.java | 3 +- .../first/wpilibj/motorcontrol/Victor.java | 3 +- .../first/wpilibj/motorcontrol/VictorSP.java | 3 +- .../edu/wpi/first/wpilibj/ADXL345_I2C.java | 4 +- .../edu/wpi/first/wpilibj/AddressableLED.java | 3 +- .../first/wpilibj/AnalogAccelerometer.java | 3 +- .../edu/wpi/first/wpilibj/AnalogEncoder.java | 3 + .../edu/wpi/first/wpilibj/AnalogGyro.java | 3 +- .../edu/wpi/first/wpilibj/AnalogInput.java | 3 +- .../main/java/edu/wpi/first/wpilibj/CAN.java | 6 +- .../edu/wpi/first/wpilibj/Compressor.java | 4 +- .../edu/wpi/first/wpilibj/DataLogManager.java | 6 +- .../edu/wpi/first/wpilibj/DigitalInput.java | 3 +- .../edu/wpi/first/wpilibj/DigitalOutput.java | 3 +- .../edu/wpi/first/wpilibj/DoubleSolenoid.java | 8 +- .../java/edu/wpi/first/wpilibj/DutyCycle.java | 3 +- .../java/edu/wpi/first/wpilibj/Encoder.java | 11 +- .../main/java/edu/wpi/first/wpilibj/I2C.java | 3 +- .../java/edu/wpi/first/wpilibj/Joystick.java | 3 +- .../main/java/edu/wpi/first/wpilibj/PWM.java | 3 +- .../edu/wpi/first/wpilibj/PneumaticHub.java | 6 + .../edu/wpi/first/wpilibj/PneumaticsBase.java | 8 + .../wpilibj/PneumaticsControlModule.java | 6 + .../wpi/first/wpilibj/PowerDistribution.java | 10 +- .../edu/wpi/first/wpilibj/Preferences.java | 3 +- .../java/edu/wpi/first/wpilibj/RobotBase.java | 106 +---- .../edu/wpi/first/wpilibj/SerialPort.java | 3 +- .../java/edu/wpi/first/wpilibj/Servo.java | 3 +- .../java/edu/wpi/first/wpilibj/SharpIR.java | 2 + .../java/edu/wpi/first/wpilibj/Solenoid.java | 4 +- .../edu/wpi/first/wpilibj/TimedRobot.java | 4 +- .../wpi/first/wpilibj/counter/Tachometer.java | 3 +- .../first/wpilibj/counter/UpDownCounter.java | 3 +- .../wpilibj/drive/DifferentialDrive.java | 11 +- .../wpi/first/wpilibj/drive/MecanumDrive.java | 7 +- .../wpilibj/motorcontrol/NidecBrushless.java | 3 +- .../smartdashboard/SmartDashboard.java | 6 +- .../java/edu/wpi/first/math/MathShared.java | 6 +- .../edu/wpi/first/math/MathSharedStore.java | 10 +- .../java/edu/wpi/first/math/MathUsageId.java | 44 -- .../math/controller/BangBangController.java | 3 +- .../first/math/controller/PIDController.java | 3 +- .../controller/ProfiledPIDController.java | 3 +- .../wpi/first/math/filter/LinearFilter.java | 3 +- .../DifferentialDriveKinematics.java | 3 +- .../kinematics/DifferentialDriveOdometry.java | 3 +- .../DifferentialDriveOdometry3d.java | 3 +- .../kinematics/MecanumDriveKinematics.java | 3 +- .../math/kinematics/MecanumDriveOdometry.java | 3 +- .../kinematics/MecanumDriveOdometry3d.java | 3 +- .../kinematics/SwerveDriveKinematics.java | 3 +- .../math/kinematics/SwerveDriveOdometry.java | 3 +- .../kinematics/SwerveDriveOdometry3d.java | 3 +- .../first/math/trajectory/TrajectoryUtil.java | 3 +- .../math/trajectory/TrapezoidProfile.java | 3 +- wpimath/src/main/native/cpp/MathShared.cpp | 2 +- .../kinematics/DifferentialDriveOdometry.cpp | 3 +- .../DifferentialDriveOdometry3d.cpp | 3 +- .../cpp/kinematics/MecanumDriveOdometry.cpp | 3 +- .../cpp/kinematics/MecanumDriveOdometry3d.cpp | 3 +- .../native/cpp/trajectory/TrajectoryUtil.cpp | 3 +- .../frc/controller/BangBangController.h | 4 +- .../include/frc/controller/PIDController.h | 4 +- .../frc/controller/ProfiledPIDController.h | 4 +- .../native/include/frc/filter/LinearFilter.h | 4 +- .../kinematics/DifferentialDriveKinematics.h | 4 +- .../frc/kinematics/MecanumDriveKinematics.h | 3 +- .../frc/kinematics/SwerveDriveKinematics.h | 6 +- .../frc/kinematics/SwerveDriveOdometry.h | 3 +- .../frc/kinematics/SwerveDriveOdometry3d.h | 3 +- .../include/frc/trajectory/TrapezoidProfile.h | 6 +- .../main/native/include/wpimath/MathShared.h | 22 +- 188 files changed, 637 insertions(+), 2298 deletions(-) create mode 100644 hal/doc/usage.adoc delete mode 100755 hal/generate_usage_reporting.py delete mode 100644 hal/src/generate/FRCNetComm.java.in delete mode 100644 hal/src/generate/FRCUsageReporting.h.in delete mode 100644 hal/src/generate/Instances.txt delete mode 100644 hal/src/generate/ResourceType.txt delete mode 100644 hal/src/generate/UsageReporting.h.in delete mode 100644 hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java delete mode 100644 hal/src/generated/main/native/include/hal/FRCUsageReporting.h delete mode 100644 hal/src/generated/main/native/include/hal/UsageReporting.h create mode 100644 hal/src/main/java/edu/wpi/first/hal/UsageReportingJNI.java create mode 100644 hal/src/main/native/cpp/UsageReporting.cpp create mode 100644 hal/src/main/native/cpp/jni/UsageReportingJNI.cpp create mode 100644 hal/src/main/native/include/hal/UsageReporting.h create mode 100644 hal/src/main/native/systemcore/UsageReporting.cpp delete mode 100644 wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java diff --git a/.github/actions/pregen/action.yml b/.github/actions/pregen/action.yml index 3c251432bf..1346a79696 100644 --- a/.github/actions/pregen/action.yml +++ b/.github/actions/pregen/action.yml @@ -18,9 +18,6 @@ runs: wget https://github.com/HebiRobotics/QuickBuffers/releases/download/1.3.3/protoc-gen-quickbuf-1.3.3-linux-x86_64.exe chmod +x protoc-gen-quickbuf-1.3.3-linux-x86_64.exe shell: bash - - name: Regenerate hal - run: ./hal/generate_usage_reporting.py - shell: bash - name: Regenerate ntcore run: ./ntcore/generate_topics.py diff --git a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java index c245c06f8b..8bf6ff07ef 100644 --- a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java +++ b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java @@ -540,9 +540,7 @@ public final class CameraServer { * @return The USB camera capturing images. */ public static UsbCamera startAutomaticCapture() { - UsbCamera camera = startAutomaticCapture(m_defaultUsbDevice.getAndIncrement()); - CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); - return camera; + return startAutomaticCapture(m_defaultUsbDevice.getAndIncrement()); } /** @@ -557,7 +555,7 @@ public final class CameraServer { public static UsbCamera startAutomaticCapture(int dev) { UsbCamera camera = new UsbCamera("USB Camera " + dev, dev); startAutomaticCapture(camera); - CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); + CameraServerSharedStore.reportUsage("UsbCamera[" + dev + "]", "auto"); return camera; } @@ -571,7 +569,7 @@ public final class CameraServer { public static UsbCamera startAutomaticCapture(String name, int dev) { UsbCamera camera = new UsbCamera(name, dev); startAutomaticCapture(camera); - CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); + CameraServerSharedStore.reportUsage("UsbCamera[" + dev + "]", "name"); return camera; } @@ -585,7 +583,7 @@ public final class CameraServer { public static UsbCamera startAutomaticCapture(String name, String path) { UsbCamera camera = new UsbCamera(name, path); startAutomaticCapture(camera); - CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle()); + CameraServerSharedStore.reportUsage("UsbCamera[" + path + "]", "path"); return camera; } diff --git a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerShared.java b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerShared.java index dfa570f85c..737aed8990 100644 --- a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerShared.java +++ b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerShared.java @@ -21,25 +21,12 @@ public interface CameraServerShared { void reportDriverStationError(String error); /** - * Report an video server usage. + * Report usage. * - * @param id the usage id + * @param resource the resource name + * @param data arbitrary string data */ - void reportVideoServer(int id); - - /** - * Report a usb camera usage. - * - * @param id the usage id - */ - void reportUsbCamera(int id); - - /** - * Report an axis camera usage. - * - * @param id the usage id - */ - void reportAxisCamera(int id); + void reportUsage(String resource, String data); /** * Get if running on a roboRIO. diff --git a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java index b129d55291..c9458c6338 100644 --- a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java +++ b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java @@ -20,17 +20,11 @@ public final class CameraServerSharedStore { cameraServerShared = new CameraServerShared() { @Override - public void reportVideoServer(int id) {} - - @Override - public void reportUsbCamera(int id) {} + public void reportUsage(String resource, String data) {} @Override public void reportDriverStationError(String error) {} - @Override - public void reportAxisCamera(int id) {} - @Override public Long getRobotMainThreadId() { return null; @@ -40,6 +34,16 @@ public final class CameraServerSharedStore { return cameraServerShared; } + /** + * Report usage. + * + * @param resource the resource name + * @param data arbitrary string data + */ + public static void reportUsage(String resource, String data) { + getCameraServerShared().reportUsage(resource, data); + } + /** * Set the CameraServerShared object. * diff --git a/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp b/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp index 35221bdffa..f92eb574bc 100644 --- a/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp +++ b/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp @@ -471,11 +471,7 @@ Instance::Instance() { } cs::UsbCamera CameraServer::StartAutomaticCapture() { - cs::UsbCamera camera = - StartAutomaticCapture(::GetInstance().m_defaultUsbDevice++); - auto csShared = GetCameraServerShared(); - csShared->ReportUsbCamera(camera.GetHandle()); - return camera; + return StartAutomaticCapture(::GetInstance().m_defaultUsbDevice++); } cs::UsbCamera CameraServer::StartAutomaticCapture(int dev) { @@ -483,7 +479,7 @@ cs::UsbCamera CameraServer::StartAutomaticCapture(int dev) { cs::UsbCamera camera{fmt::format("USB Camera {}", dev), dev}; StartAutomaticCapture(camera); auto csShared = GetCameraServerShared(); - csShared->ReportUsbCamera(camera.GetHandle()); + csShared->ReportUsage(fmt::format("UsbCamera[{}]", dev), "auto"); return camera; } @@ -493,7 +489,7 @@ cs::UsbCamera CameraServer::StartAutomaticCapture(std::string_view name, cs::UsbCamera camera{name, dev}; StartAutomaticCapture(camera); auto csShared = GetCameraServerShared(); - csShared->ReportUsbCamera(camera.GetHandle()); + csShared->ReportUsage(fmt::format("UsbCamera[{}]", dev), "name"); return camera; } @@ -503,7 +499,7 @@ cs::UsbCamera CameraServer::StartAutomaticCapture(std::string_view name, cs::UsbCamera camera{name, path}; StartAutomaticCapture(camera); auto csShared = GetCameraServerShared(); - csShared->ReportUsbCamera(camera.GetHandle()); + csShared->ReportUsage(fmt::format("UsbCamera[{}]", path), "path"); return camera; } diff --git a/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp b/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp index 0dc1388f00..bf4d1df2d6 100644 --- a/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp +++ b/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp @@ -12,9 +12,7 @@ namespace { class DefaultCameraServerShared : public frc::CameraServerShared { public: - void ReportUsbCamera(int id) override {} - void ReportAxisCamera(int id) override {} - void ReportVideoServer(int id) override {} + void ReportUsage(std::string_view resource, std::string_view data) override {} void SetCameraServerErrorV(fmt::string_view format, fmt::format_args args) override {} void SetVisionRunnerErrorV(fmt::string_view format, diff --git a/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h b/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h index a95d322995..0c8889f5fd 100644 --- a/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h +++ b/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h @@ -5,6 +5,7 @@ #pragma once #include +#include #include #include @@ -14,9 +15,8 @@ namespace frc { class CameraServerShared { public: virtual ~CameraServerShared() = default; - virtual void ReportUsbCamera(int id) = 0; - virtual void ReportAxisCamera(int id) = 0; - virtual void ReportVideoServer(int id) = 0; + virtual void ReportUsage(std::string_view resource, + std::string_view data) = 0; virtual void SetCameraServerErrorV(fmt::string_view format, fmt::format_args args) = 0; virtual void SetVisionRunnerErrorV(fmt::string_view format, diff --git a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java index 24520f5647..28380a70e6 100644 --- a/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java +++ b/epilogue-processor/src/main/java/edu/wpi/first/epilogue/processor/EpilogueGenerator.java @@ -55,7 +55,6 @@ public class EpilogueGenerator { out.println("import static edu.wpi.first.units.Units.Seconds;"); out.println(); - out.println("import edu.wpi.first.hal.FRCNetComm;"); out.println("import edu.wpi.first.hal.HAL;"); out.println(); @@ -89,10 +88,7 @@ public class EpilogueGenerator { out.println( """ static { - HAL.report( - FRCNetComm.tResourceType.kResourceType_LoggingFramework, - FRCNetComm.tInstances.kLoggingFramework_Epilogue - ); + HAL.reportUsage("Epilogue", ""); } """); diff --git a/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java index 1e9806d3a2..65a1dde8ed 100644 --- a/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java +++ b/epilogue-processor/src/test/java/edu/wpi/first/epilogue/processor/EpilogueGeneratorTest.java @@ -33,17 +33,13 @@ class EpilogueGeneratorTest { import static edu.wpi.first.units.Units.Seconds; - import edu.wpi.first.hal.FRCNetComm; import edu.wpi.first.hal.HAL; import edu.wpi.first.epilogue.ExampleLogger; public final class Epilogue { static { - HAL.report( - FRCNetComm.tResourceType.kResourceType_LoggingFramework, - FRCNetComm.tInstances.kLoggingFramework_Epilogue - ); + HAL.reportUsage("Epilogue", ""); } private static final EpilogueConfiguration config = new EpilogueConfiguration(); @@ -92,17 +88,13 @@ class EpilogueGeneratorTest { import static edu.wpi.first.units.Units.Seconds; - import edu.wpi.first.hal.FRCNetComm; import edu.wpi.first.hal.HAL; import edu.wpi.first.epilogue.ExampleLogger; public final class Epilogue { static { - HAL.report( - FRCNetComm.tResourceType.kResourceType_LoggingFramework, - FRCNetComm.tInstances.kLoggingFramework_Epilogue - ); + HAL.reportUsage("Epilogue", ""); } private static final EpilogueConfiguration config = new EpilogueConfiguration(); @@ -146,17 +138,13 @@ class EpilogueGeneratorTest { import static edu.wpi.first.units.Units.Seconds; - import edu.wpi.first.hal.FRCNetComm; import edu.wpi.first.hal.HAL; import edu.wpi.first.epilogue.ExampleLogger; public final class Epilogue { static { - HAL.report( - FRCNetComm.tResourceType.kResourceType_LoggingFramework, - FRCNetComm.tInstances.kLoggingFramework_Epilogue - ); + HAL.reportUsage("Epilogue", ""); } private static final EpilogueConfiguration config = new EpilogueConfiguration(); @@ -234,7 +222,6 @@ class EpilogueGeneratorTest { import static edu.wpi.first.units.Units.Seconds; - import edu.wpi.first.hal.FRCNetComm; import edu.wpi.first.hal.HAL; import edu.wpi.first.epilogue.AlphaBotLogger; @@ -242,10 +229,7 @@ class EpilogueGeneratorTest { public final class Epilogue { static { - HAL.report( - FRCNetComm.tResourceType.kResourceType_LoggingFramework, - FRCNetComm.tInstances.kLoggingFramework_Epilogue - ); + HAL.reportUsage("Epilogue", ""); } private static final EpilogueConfiguration config = new EpilogueConfiguration(); @@ -371,7 +355,6 @@ class EpilogueGeneratorTest { import static edu.wpi.first.units.Units.Seconds; - import edu.wpi.first.hal.FRCNetComm; import edu.wpi.first.hal.HAL; import edu.wpi.first.epilogue.ExampleLogger; @@ -379,10 +362,7 @@ class EpilogueGeneratorTest { public final class Epilogue { static { - HAL.report( - FRCNetComm.tResourceType.kResourceType_LoggingFramework, - FRCNetComm.tInstances.kLoggingFramework_Epilogue - ); + HAL.reportUsage("Epilogue", ""); } private static final EpilogueConfiguration config = new EpilogueConfiguration(); diff --git a/hal/BUILD.bazel b/hal/BUILD.bazel index 2a1c00a1fc..ce7368560d 100644 --- a/hal/BUILD.bazel +++ b/hal/BUILD.bazel @@ -3,14 +3,6 @@ load("@rules_java//java:defs.bzl", "java_binary") load("//shared/bazel/rules:java_rules.bzl", "wpilib_java_junit5_test") load("//shared/bazel/rules:jni_rules.bzl", "wpilib_jni_cc_library", "wpilib_jni_java_library") -cc_library( - name = "generated_cc_headers", - hdrs = glob(["src/generated/main/native/include/**"]), - includes = ["src/generated/main/native/include"], - strip_include_prefix = "src/generated/main/native/include", - visibility = ["//hal:__subpackages__"], -) - cc_library( name = "mrc_cc_headers", hdrs = glob(["src/mrc/include/**"]), @@ -27,12 +19,6 @@ cc_library( visibility = ["//hal:__subpackages__"], ) -filegroup( - name = "generated_java", - srcs = glob(["src/generated/main/java/**/*.java"]), - visibility = ["//hal:__subpackages__"], -) - SYSTEMCORE_SRCS = glob(["src/main/native/systemcore/**"]) SIM_SRCS = glob(["src/main/native/sim/**"]) @@ -59,7 +45,6 @@ cc_library( strip_include_prefix = "src/main/native/include", visibility = ["//visibility:public"], deps = [ - ":generated_cc_headers", ":generated_mrc_cc_headers", ":mrc_cc_headers", "//ntcore:ntcore.static", @@ -80,7 +65,7 @@ wpilib_jni_cc_library( wpilib_jni_java_library( name = "hal-java", - srcs = [":generated_java"] + glob(["src/main/java/**/*.java"]), + srcs = glob(["src/main/java/**/*.java"]), native_libs = [":wpiHaljni"], visibility = ["//visibility:public"], deps = [ diff --git a/hal/CMakeLists.txt b/hal/CMakeLists.txt index 84a5555491..311231c00d 100644 --- a/hal/CMakeLists.txt +++ b/hal/CMakeLists.txt @@ -19,7 +19,6 @@ target_include_directories( hal PUBLIC $ - $ $ ) target_link_libraries(hal PUBLIC ntcore wpiutil) @@ -29,7 +28,6 @@ set_property(TARGET hal PROPERTY FOLDER "libraries") install(TARGETS hal EXPORT hal) export(TARGETS hal FILE hal.cmake NAMESPACE hal::) install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/hal") -install(DIRECTORY src/generated/main/native/include/ DESTINATION "${include_dest}/hal") configure_file(hal-config.cmake.in ${WPILIB_BINARY_DIR}/hal-config.cmake) install(FILES ${WPILIB_BINARY_DIR}/hal-config.cmake DESTINATION share/hal) @@ -41,7 +39,7 @@ if(WITH_JAVA) file(GLOB_RECURSE hal_shared_jni_src src/main/native/cpp/jni/*.cpp) - file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java src/generated/main/java/*.java) + file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java) set(CMAKE_JNI_TARGET true) add_jar( @@ -77,9 +75,7 @@ if(WITH_JAVA_SOURCE) include(CreateSourceJar) add_source_jar( hal_src_jar - BASE_DIRECTORIES - ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java - ${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/java + BASE_DIRECTORIES ${CMAKE_CURRENT_SOURCE_DIR}/src/main/java OUTPUT_NAME wpiHal-sources OUTPUT_DIR ${WPILIB_BINARY_DIR}/${java_lib_dest} ) diff --git a/hal/doc/usage.adoc b/hal/doc/usage.adoc new file mode 100644 index 0000000000..627756cffc --- /dev/null +++ b/hal/doc/usage.adoc @@ -0,0 +1,70 @@ += WPILib Usage Reporting Guidelines, Version 1.0 +WPILib Developers +Revision 1.0 (0x0100), 2/4/2025 +:toc: +:toc-placement: preamble +:sectanchors: + +Guidelines for reporting of utilization of hardware resources and software features using the WPILib HAL usage reporting API (HAL_ReportUsage). + +[[motivation]] +== Motivation + +WPILib and associated vendor libraries offer a large number of different hardware and software features. Collecting aggregate information on what features are used by teams on their competition robots enables FIRST, the WPILib development team, and vendors to make development plans and decide which features may be worth adding or removing in future years. + +The usage reporting infrastructure may also be used to provide other features, such as interactive debugging (sensor reading and motor control) independent of the user program to verify the software-hardware IO (e.g. wiring) configuration independent of software code operation. + +As the usage reporting infrastructure is a shared resource using string names and string values, guidelines are warranted to enable consistency of use and avoidance of accidental naming conflicts across the software ecosystem. Resource names must be unique for each unique resource to ensure no usage information is lost. Many resources also have associated unique indices, such as bus or device IDs or port numbers, and a standard approach to formatting these into strings is desirable from a consistency perspective. + +[[references]] +== References + +[[rfc7159,RFC7159,JSON]] +* RFC 7159, The JavaScript Object Notation (JSON) Data Interchange Format, https://tools.ietf.org/html/rfc7159 + +[[api-contract]] +== API Contract + +The WPILib HAL usage reporting API is a single function that takes two strings: a resource name and an associated data value. This function operates like a dictionary put function: calling the function multiple times with the same resource name results in *replacing* the data value associated with that resource name; only the data value from the last call to the function for each resource name will be reported/retained by the usage reporting system. There is no mechanism to un-report a resource. Usage reporting is empty at the start of the user program. + +[[resource-names]] +== Resource Names + +Resource names are UTF-8 strings, structured into the following components: + +- Abbreviated vendor name, followed by a forward slash (``/``). This component is not present for WPILib resources (no name or slash). +- Optional short package name, followed by a period (``.``). This should be 10 characters or less, and should only be present if required for disambiguation in very large libraries. +- Core resource name +- Optional bus index or name, wrapped in square brackets (``[index]``). Indexes should use decimal representation. +- Optional device index or name, wrapped in square brackets. May be repeated as required. +- Optional port number, wrapped in square brackets. If multiple ports are used for a single logical resource, they may be comma-separated (e.g. ``[3,4]``). +- Optional forward slash, followed by additional core resource+bus+device+port components, as required + +When choosing a core resource name, using a class name or device type is often the best choice. The main exception to this are IO resources which can be allocated to only a single device (e.g. a DIO pin or joystick port). In that case, a better choice is to use the IO name as the resource name, and store the class name or device type in the data value. + +[[data-values]] +== Data Values + +Data values may be blank if not required or useful. For simple values, a simple string or number (represented in decimal) can be directly stored. For complex data values (e.g. to represent a combination of features being used), JSON encoding is strongly recommended. In general, the total size of the data value should be minimized. + +A common use case for a data value is a count of the number of times a particular resource is used. Note the API does not have provisions for auto-incrementing a usage count; callers must handle this (e.g. through use of a static counter). + +[[examples]] +== Examples + +[cols="3,2,2", options="header"] +|=== +|Use Case|Name|Value +|SwerveDriveKinematics class|``SwerveDriveKinematics``|Empty +|Java programming language|``Language``|``Java`` +|PID Controller (4th instantiation)|``PIDController``|``4`` +|XBox Controller attached to port 3|``HID[3]``|``XboxController`` +|Digital input on IO 2|``IO[2]``|``DigitalInput`` +|Quadrature Encoder on IO 3 and 4|``IO[3,4]``|``Encoder`` +|PCM Solenoid, CAN bus 0, ID 3, port 2|``PCM[0][3]/Solenoid[2]``|Empty +|PH Compressor, CAN bus 0, ID 1|``PH[0][1]/Compressor``|Empty +|Servo on IO 5|``IO[5]``|``Servo`` +|Generic CAN device, bus 1, type 3, mfg 4, ID 2|``CAN[1][3][4][2]``|Empty +|CTRE Kraken, CAN bus 0, ID 50|``CTRE/Kraken[0][50]``|Vendor-specified +|Rev SparkMax, CAN bus 1, ID 3|``Rev/SparkMax[1][3]``|Vendor-specified +|=== diff --git a/hal/generate_usage_reporting.py b/hal/generate_usage_reporting.py deleted file mode 100755 index a495673d87..0000000000 --- a/hal/generate_usage_reporting.py +++ /dev/null @@ -1,109 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright (c) FIRST and other WPILib contributors. -# Open Source Software; you can modify and/or share it under the terms of -# the WPILib BSD license file in the root directory of this project. - -import argparse -from pathlib import Path - - -def generate_usage_reporting(output_directory: Path, template_directory: Path): - # Gets the folder this script is in (the hal/ directory) - java_package = "edu/wpi/first/hal" - # fmt: off - (output_directory / "main/native/include/hal").mkdir(parents=True, exist_ok=True) - (output_directory / f"main/java/{java_package}").mkdir(parents=True, exist_ok=True) - # fmt: on - usage_reporting_types_cpp = [] - usage_reporting_instances_cpp = [] - usage_reporting_types = [] - usage_reporting_instances = [] - with (template_directory / "Instances.txt").open(encoding="utf-8") as instances: - for instance in instances: - usage_reporting_instances_cpp.append(f" {instance.strip()},") - usage_reporting_instances.append( - f" /** {instance.strip()}. */\n" - f" public static final int {instance.strip()};" - ) - - with (template_directory / "ResourceType.txt").open( - encoding="utf-8" - ) as resource_types: - for resource_type in resource_types: - usage_reporting_types_cpp.append(f" {resource_type.strip()},") - usage_reporting_types.append( - f" /** {resource_type.strip()}. */\n" - f" public static final int {resource_type.strip()};" - ) - - with (template_directory / "FRCNetComm.java.in").open( - encoding="utf-8" - ) as java_usage_reporting: - contents = ( - # fmt: off - java_usage_reporting.read() - .replace(r"${usage_reporting_types}", "\n".join(usage_reporting_types)) - .replace(r"${usage_reporting_instances}", "\n".join(usage_reporting_instances)) - # fmt: on - ) - - frc_net_comm = output_directory / f"main/java/{java_package}/FRCNetComm.java" - frc_net_comm.write_text(contents, encoding="utf-8", newline="\n") - - with (template_directory / "FRCUsageReporting.h.in").open( - encoding="utf-8" - ) as cpp_usage_reporting: - contents = ( - # fmt: off - cpp_usage_reporting.read() - .replace(r"${usage_reporting_types_cpp}", "\n".join(usage_reporting_types_cpp)) - .replace(r"${usage_reporting_instances_cpp}", "\n".join(usage_reporting_instances_cpp)) - # fmt: on - ) - - usage_reporting_hdr = ( - output_directory / "main/native/include/hal/FRCUsageReporting.h" - ) - usage_reporting_hdr.write_text(contents, encoding="utf-8", newline="\n") - - with (template_directory / "UsageReporting.h.in").open( - encoding="utf-8" - ) as cpp_usage_reporting: - contents = ( - # fmt: off - cpp_usage_reporting.read() - .replace(r"${usage_reporting_types_cpp}", "\n".join(usage_reporting_types_cpp)) - .replace(r"${usage_reporting_instances_cpp}", "\n".join(usage_reporting_instances_cpp)) - # fmt: on - ) - - usage_reporting_hdr = ( - output_directory / "main/native/include/hal/UsageReporting.h" - ) - usage_reporting_hdr.write_text(contents, encoding="utf-8", newline="\n") - - -def main(): - dirname = Path(__file__).parent - - parser = argparse.ArgumentParser() - parser.add_argument( - "--output_directory", - help="Optional. If set, will output the generated files to this directory, otherwise it will use a path relative to the script", - default=dirname / "src/generated", - type=Path, - ) - parser.add_argument( - "--template_root", - help="Optional. If set, will use this directory as the root for the jinja templates", - default=dirname / "src/generate", - type=Path, - ) - args = parser.parse_args() - - generate_usage_reporting(args.output_directory, args.template_root) - - -if __name__ == "__main__": - main() diff --git a/hal/src/generate/FRCNetComm.java.in b/hal/src/generate/FRCNetComm.java.in deleted file mode 100644 index d8ce4ccacc..0000000000 --- a/hal/src/generate/FRCNetComm.java.in +++ /dev/null @@ -1,38 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./hal/generate_usage_reporting.py. DO NOT MODIFY - -package edu.wpi.first.hal; - -/** - * JNI wrapper for library FRC_NetworkCommunication
. - */ -@SuppressWarnings("PMD.MissingStaticMethodInNonInstantiatableClass") -public final class FRCNetComm { - /** - * Resource type from UsageReporting. - */ - @SuppressWarnings("TypeName") - public static final class tResourceType { - private tResourceType() { - } - -${usage_reporting_types} - } - - /** - * Instances from UsageReporting. - */ - @SuppressWarnings("TypeName") - public static final class tInstances { - private tInstances() { - } - -${usage_reporting_instances} - } - - /** Utility class. */ - private FRCNetComm() {} -} diff --git a/hal/src/generate/FRCUsageReporting.h.in b/hal/src/generate/FRCUsageReporting.h.in deleted file mode 100644 index 03a78f0cbc..0000000000 --- a/hal/src/generate/FRCUsageReporting.h.in +++ /dev/null @@ -1,60 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./hal/generate_usage_reporting.py. DO NOT MODIFY - -#pragma once - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -// ifdef's definition is to allow for default parameters in C++. -#ifdef __cplusplus -/** - * Reports a hardware usage to the HAL. - * - * @param resource the used resource - * @param instanceNumber the instance of the resource - * @param context a user specified context index - * @param feature a user specified feature string - * @return the index of the added value in NetComm - */ -int64_t HAL_Report(int32_t resource, int32_t instanceNumber, - int32_t context = 0, const char* feature = nullptr); -#else - -/** - * Reports a hardware usage to the HAL. - * - * @param resource the used resource - * @param instanceNumber the instance of the resource - * @param context a user specified context index - * @param feature a user specified feature string - * @return the index of the added value in NetComm - */ -int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context, - const char* feature); -#endif - -#ifdef __cplusplus -} -#endif - -/* - * Autogenerated file! Do not manually edit this file. - */ - -#ifdef __cplusplus -namespace HALUsageReporting { - enum tResourceType : int32_t { -${usage_reporting_types_cpp} - }; - enum tInstances : int32_t { -${usage_reporting_instances_cpp} - }; -} -#endif diff --git a/hal/src/generate/Instances.txt b/hal/src/generate/Instances.txt deleted file mode 100644 index 20d2738d9a..0000000000 --- a/hal/src/generate/Instances.txt +++ /dev/null @@ -1,80 +0,0 @@ -kLanguage_LabVIEW = 1 -kLanguage_CPlusPlus = 2 -kLanguage_Java = 3 -kLanguage_Python = 4 -kLanguage_DotNet = 5 -kLanguage_Kotlin = 6 -kLanguage_Rust = 7 -kCANPlugin_BlackJagBridge = 1 -kCANPlugin_2CAN = 2 -kFramework_Iterative = 1 -kFramework_Simple = 2 -kFramework_CommandControl = 3 -kFramework_Timed = 4 -kFramework_ROS = 5 -kFramework_RobotBuilder = 6 -kFramework_AdvantageKit = 7 -kFramework_MagicBot = 8 -kRobotDrive_ArcadeStandard = 1 -kRobotDrive_ArcadeButtonSpin = 2 -kRobotDrive_ArcadeRatioCurve = 3 -kRobotDrive_Tank = 4 -kRobotDrive_MecanumPolar = 5 -kRobotDrive_MecanumCartesian = 6 -kRobotDrive2_DifferentialArcade = 7 -kRobotDrive2_DifferentialTank = 8 -kRobotDrive2_DifferentialCurvature = 9 -kRobotDrive2_MecanumCartesian = 10 -kRobotDrive2_MecanumPolar = 11 -kRobotDrive2_KilloughCartesian = 12 -kRobotDrive2_KilloughPolar = 13 -kRobotDriveSwerve_Other = 14 -kRobotDriveSwerve_YAGSL = 15 -kRobotDriveSwerve_CTRE = 16 -kRobotDriveSwerve_MaxSwerve = 17 -kRobotDriveSwerve_AdvantageKit = 18 -kDriverStationCIO_Analog = 1 -kDriverStationCIO_DigitalIn = 2 -kDriverStationCIO_DigitalOut = 3 -kDriverStationEIO_Acceleration = 1 -kDriverStationEIO_AnalogIn = 2 -kDriverStationEIO_AnalogOut = 3 -kDriverStationEIO_Button = 4 -kDriverStationEIO_LED = 5 -kDriverStationEIO_DigitalIn = 6 -kDriverStationEIO_DigitalOut = 7 -kDriverStationEIO_FixedDigitalOut = 8 -kDriverStationEIO_PWM = 9 -kDriverStationEIO_Encoder = 10 -kDriverStationEIO_TouchSlider = 11 -kADXL345_SPI = 1 -kADXL345_I2C = 2 -kCommand_Scheduler = 1 -kCommand2_Scheduler = 2 -kSmartDashboard_Instance = 1 -kSmartDashboard_LiveWindow = 2 -kKinematics_DifferentialDrive = 1 -kKinematics_MecanumDrive = 2 -kKinematics_SwerveDrive = 3 -kOdometry_DifferentialDrive = 1 -kOdometry_MecanumDrive = 2 -kOdometry_SwerveDrive = 3 -kDashboard_Unknown = 1 -kDashboard_Glass = 2 -kDashboard_SmartDashboard = 3 -kDashboard_Shuffleboard = 4 -kDashboard_Elastic = 5 -kDashboard_LabVIEW = 6 -kDashboard_AdvantageScope = 7 -kDashboard_QFRCDashboard = 8 -kDashboard_FRCWebComponents = 9 -kDataLogLocation_Onboard = 1 -kDataLogLocation_USB = 2 -kLoggingFramework_Other = 1 -kLoggingFramework_Epilogue = 2 -kLoggingFramework_Monologue = 3 -kLoggingFramework_AdvantageKit = 4 -kLoggingFramework_DogLog = 5 -kPDP_CTRE = 1 -kPDP_REV = 2 -kPDP_Unknown = 3 diff --git a/hal/src/generate/ResourceType.txt b/hal/src/generate/ResourceType.txt deleted file mode 100644 index a275ff7aff..0000000000 --- a/hal/src/generate/ResourceType.txt +++ /dev/null @@ -1,127 +0,0 @@ -kResourceType_Controller = 0 -kResourceType_Module = 1 -kResourceType_Language = 2 -kResourceType_CANPlugin = 3 -kResourceType_Accelerometer = 4 -kResourceType_ADXL345 = 5 -kResourceType_AnalogChannel = 6 -kResourceType_AnalogTrigger = 7 -kResourceType_AnalogTriggerOutput = 8 -kResourceType_CANJaguar = 9 -kResourceType_Compressor = 10 -kResourceType_Counter = 11 -kResourceType_Dashboard = 12 -kResourceType_DigitalInput = 13 -kResourceType_DigitalOutput = 14 -kResourceType_DriverStationCIO = 15 -kResourceType_DriverStationEIO = 16 -kResourceType_DriverStationLCD = 17 -kResourceType_Encoder = 18 -kResourceType_GearTooth = 19 -kResourceType_Gyro = 20 -kResourceType_I2C = 21 -kResourceType_Framework = 22 -kResourceType_Jaguar = 23 -kResourceType_Joystick = 24 -kResourceType_Kinect = 25 -kResourceType_KinectStick = 26 -kResourceType_PIDController = 27 -kResourceType_Preferences = 28 -kResourceType_PWM = 29 -kResourceType_Relay = 30 -kResourceType_RobotDrive = 31 -kResourceType_SerialPort = 32 -kResourceType_Servo = 33 -kResourceType_Solenoid = 34 -kResourceType_SPI = 35 -kResourceType_Task = 36 -kResourceType_Ultrasonic = 37 -kResourceType_Victor = 38 -kResourceType_Button = 39 -kResourceType_Command = 40 -kResourceType_AxisCamera = 41 -kResourceType_PCVideoServer = 42 -kResourceType_SmartDashboard = 43 -kResourceType_Talon = 44 -kResourceType_HiTechnicColorSensor = 45 -kResourceType_HiTechnicAccel = 46 -kResourceType_HiTechnicCompass = 47 -kResourceType_SRF08 = 48 -kResourceType_AnalogOutput = 49 -kResourceType_VictorSP = 50 -kResourceType_PWMTalonSRX = 51 -kResourceType_CANTalonSRX = 52 -kResourceType_ADXL362 = 53 -kResourceType_ADXRS450 = 54 -kResourceType_RevSPARK = 55 -kResourceType_MindsensorsSD540 = 56 -kResourceType_DigitalGlitchFilter = 57 -kResourceType_ADIS16448 = 58 -kResourceType_PDP = 59 -kResourceType_PCM = 60 -kResourceType_PigeonIMU = 61 -kResourceType_NidecBrushless = 62 -kResourceType_CANifier = 63 -kResourceType_TalonFX = 64 -kResourceType_CTRE_future1 = 65 -kResourceType_CTRE_future2 = 66 -kResourceType_CTRE_future3 = 67 -kResourceType_CTRE_future4 = 68 -kResourceType_CTRE_future5 = 69 -kResourceType_CTRE_future6 = 70 -kResourceType_LinearFilter = 71 -kResourceType_XboxController = 72 -kResourceType_UsbCamera = 73 -kResourceType_NavX = 74 -kResourceType_Pixy = 75 -kResourceType_Pixy2 = 76 -kResourceType_ScanseSweep = 77 -kResourceType_Shuffleboard = 78 -kResourceType_CAN = 79 -kResourceType_DigilentDMC60 = 80 -kResourceType_PWMVictorSPX = 81 -kResourceType_RevSparkMaxPWM = 82 -kResourceType_RevSparkMaxCAN = 83 -kResourceType_ADIS16470 = 84 -kResourceType_PIDController2 = 85 -kResourceType_ProfiledPIDController = 86 -kResourceType_Kinematics = 87 -kResourceType_Odometry = 88 -kResourceType_Units = 89 -kResourceType_TrapezoidProfile = 90 -kResourceType_DutyCycle = 91 -kResourceType_AddressableLEDs = 92 -kResourceType_FusionVenom = 93 -kResourceType_CTRE_future7 = 94 -kResourceType_CTRE_future8 = 95 -kResourceType_CTRE_future9 = 96 -kResourceType_CTRE_future10 = 97 -kResourceType_CTRE_future11 = 98 -kResourceType_CTRE_future12 = 99 -kResourceType_CTRE_future13 = 100 -kResourceType_CTRE_future14 = 101 -kResourceType_ExponentialProfile = 102 -kResourceType_PS4Controller = 103 -kResourceType_PhotonCamera = 104 -kResourceType_PhotonPoseEstimator = 105 -kResourceType_PathPlannerPath = 106 -kResourceType_PathPlannerAuto = 107 -kResourceType_PathFindingCommand = 108 -kResourceType_Redux_future1 = 109 -kResourceType_Redux_future2 = 110 -kResourceType_Redux_future3 = 111 -kResourceType_Redux_future4 = 112 -kResourceType_Redux_future5 = 113 -kResourceType_RevSparkFlexCAN = 114 -kResourceType_RevSparkFlexPWM = 115 -kResourceType_BangBangController = 116 -kResourceType_DataLogManager = 117 -kResourceType_LoggingFramework = 118 -kResourceType_ChoreoTrajectory = 119 -kResourceType_ChoreoTrigger = 120 -kResourceType_PathWeaverTrajectory = 121 -kResourceType_Koors40 = 122 -kResourceType_ThriftyNova = 123 -kResourceType_RevServoHub = 124 -kResourceType_PWFSEN36005 = 125 -kResourceType_LaserShark = 126 diff --git a/hal/src/generate/UsageReporting.h.in b/hal/src/generate/UsageReporting.h.in deleted file mode 100644 index f905257562..0000000000 --- a/hal/src/generate/UsageReporting.h.in +++ /dev/null @@ -1,55 +0,0 @@ - -#ifndef __UsageReporting_h__ -#define __UsageReporting_h__ - -#ifdef _WIN32 -#include -#define EXPORT_FUNC __declspec(dllexport) __cdecl -#elif defined(__vxworks) -#include -#define EXPORT_FUNC -#else -#include -#include -#define EXPORT_FUNC -#endif - -#define kUsageReporting_version 1 - -namespace nUsageReporting -{ -typedef enum -{ -${usage_reporting_types_cpp} - -// kResourceType_MaximumID = 255, -} tResourceType; - -typedef enum -{ -${usage_reporting_instances_cpp} -} tInstances; - -/** - * Report the usage of a resource of interest. - * - * @param resource one of the values in the tResourceType above (max value 51). - * @param instanceNumber an index that identifies the resource instance. - * @param context an optional additional context number for some cases (such as module number). Set to 0 to omit. - * @param feature a string to be included describing features in use on a specific resource. Setting the same resource more than once allows you to change the feature string. - */ -uint32_t EXPORT_FUNC report(tResourceType resource, uint8_t instanceNumber, uint8_t context = 0, const char* feature = NULL); -} // namespace nUsageReporting - -#ifdef __cplusplus -extern "C" -{ -#endif - - uint32_t EXPORT_FUNC FRC_NetworkCommunication_nUsageReporting_report(uint8_t resource, uint8_t instanceNumber, uint8_t context, const char* feature); - -#ifdef __cplusplus -} -#endif - -#endif // __UsageReporting_h__ diff --git a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java deleted file mode 100644 index 30ba993033..0000000000 --- a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java +++ /dev/null @@ -1,450 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./hal/generate_usage_reporting.py. DO NOT MODIFY - -package edu.wpi.first.hal; - -/** - * JNI wrapper for library FRC_NetworkCommunication
. - */ -@SuppressWarnings("PMD.MissingStaticMethodInNonInstantiatableClass") -public final class FRCNetComm { - /** - * Resource type from UsageReporting. - */ - @SuppressWarnings("TypeName") - public static final class tResourceType { - private tResourceType() { - } - - /** kResourceType_Controller = 0. */ - public static final int kResourceType_Controller = 0; - /** kResourceType_Module = 1. */ - public static final int kResourceType_Module = 1; - /** kResourceType_Language = 2. */ - public static final int kResourceType_Language = 2; - /** kResourceType_CANPlugin = 3. */ - public static final int kResourceType_CANPlugin = 3; - /** kResourceType_Accelerometer = 4. */ - public static final int kResourceType_Accelerometer = 4; - /** kResourceType_ADXL345 = 5. */ - public static final int kResourceType_ADXL345 = 5; - /** kResourceType_AnalogChannel = 6. */ - public static final int kResourceType_AnalogChannel = 6; - /** kResourceType_AnalogTrigger = 7. */ - public static final int kResourceType_AnalogTrigger = 7; - /** kResourceType_AnalogTriggerOutput = 8. */ - public static final int kResourceType_AnalogTriggerOutput = 8; - /** kResourceType_CANJaguar = 9. */ - public static final int kResourceType_CANJaguar = 9; - /** kResourceType_Compressor = 10. */ - public static final int kResourceType_Compressor = 10; - /** kResourceType_Counter = 11. */ - public static final int kResourceType_Counter = 11; - /** kResourceType_Dashboard = 12. */ - public static final int kResourceType_Dashboard = 12; - /** kResourceType_DigitalInput = 13. */ - public static final int kResourceType_DigitalInput = 13; - /** kResourceType_DigitalOutput = 14. */ - public static final int kResourceType_DigitalOutput = 14; - /** kResourceType_DriverStationCIO = 15. */ - public static final int kResourceType_DriverStationCIO = 15; - /** kResourceType_DriverStationEIO = 16. */ - public static final int kResourceType_DriverStationEIO = 16; - /** kResourceType_DriverStationLCD = 17. */ - public static final int kResourceType_DriverStationLCD = 17; - /** kResourceType_Encoder = 18. */ - public static final int kResourceType_Encoder = 18; - /** kResourceType_GearTooth = 19. */ - public static final int kResourceType_GearTooth = 19; - /** kResourceType_Gyro = 20. */ - public static final int kResourceType_Gyro = 20; - /** kResourceType_I2C = 21. */ - public static final int kResourceType_I2C = 21; - /** kResourceType_Framework = 22. */ - public static final int kResourceType_Framework = 22; - /** kResourceType_Jaguar = 23. */ - public static final int kResourceType_Jaguar = 23; - /** kResourceType_Joystick = 24. */ - public static final int kResourceType_Joystick = 24; - /** kResourceType_Kinect = 25. */ - public static final int kResourceType_Kinect = 25; - /** kResourceType_KinectStick = 26. */ - public static final int kResourceType_KinectStick = 26; - /** kResourceType_PIDController = 27. */ - public static final int kResourceType_PIDController = 27; - /** kResourceType_Preferences = 28. */ - public static final int kResourceType_Preferences = 28; - /** kResourceType_PWM = 29. */ - public static final int kResourceType_PWM = 29; - /** kResourceType_Relay = 30. */ - public static final int kResourceType_Relay = 30; - /** kResourceType_RobotDrive = 31. */ - public static final int kResourceType_RobotDrive = 31; - /** kResourceType_SerialPort = 32. */ - public static final int kResourceType_SerialPort = 32; - /** kResourceType_Servo = 33. */ - public static final int kResourceType_Servo = 33; - /** kResourceType_Solenoid = 34. */ - public static final int kResourceType_Solenoid = 34; - /** kResourceType_SPI = 35. */ - public static final int kResourceType_SPI = 35; - /** kResourceType_Task = 36. */ - public static final int kResourceType_Task = 36; - /** kResourceType_Ultrasonic = 37. */ - public static final int kResourceType_Ultrasonic = 37; - /** kResourceType_Victor = 38. */ - public static final int kResourceType_Victor = 38; - /** kResourceType_Button = 39. */ - public static final int kResourceType_Button = 39; - /** kResourceType_Command = 40. */ - public static final int kResourceType_Command = 40; - /** kResourceType_AxisCamera = 41. */ - public static final int kResourceType_AxisCamera = 41; - /** kResourceType_PCVideoServer = 42. */ - public static final int kResourceType_PCVideoServer = 42; - /** kResourceType_SmartDashboard = 43. */ - public static final int kResourceType_SmartDashboard = 43; - /** kResourceType_Talon = 44. */ - public static final int kResourceType_Talon = 44; - /** kResourceType_HiTechnicColorSensor = 45. */ - public static final int kResourceType_HiTechnicColorSensor = 45; - /** kResourceType_HiTechnicAccel = 46. */ - public static final int kResourceType_HiTechnicAccel = 46; - /** kResourceType_HiTechnicCompass = 47. */ - public static final int kResourceType_HiTechnicCompass = 47; - /** kResourceType_SRF08 = 48. */ - public static final int kResourceType_SRF08 = 48; - /** kResourceType_AnalogOutput = 49. */ - public static final int kResourceType_AnalogOutput = 49; - /** kResourceType_VictorSP = 50. */ - public static final int kResourceType_VictorSP = 50; - /** kResourceType_PWMTalonSRX = 51. */ - public static final int kResourceType_PWMTalonSRX = 51; - /** kResourceType_CANTalonSRX = 52. */ - public static final int kResourceType_CANTalonSRX = 52; - /** kResourceType_ADXL362 = 53. */ - public static final int kResourceType_ADXL362 = 53; - /** kResourceType_ADXRS450 = 54. */ - public static final int kResourceType_ADXRS450 = 54; - /** kResourceType_RevSPARK = 55. */ - public static final int kResourceType_RevSPARK = 55; - /** kResourceType_MindsensorsSD540 = 56. */ - public static final int kResourceType_MindsensorsSD540 = 56; - /** kResourceType_DigitalGlitchFilter = 57. */ - public static final int kResourceType_DigitalGlitchFilter = 57; - /** kResourceType_ADIS16448 = 58. */ - public static final int kResourceType_ADIS16448 = 58; - /** kResourceType_PDP = 59. */ - public static final int kResourceType_PDP = 59; - /** kResourceType_PCM = 60. */ - public static final int kResourceType_PCM = 60; - /** kResourceType_PigeonIMU = 61. */ - public static final int kResourceType_PigeonIMU = 61; - /** kResourceType_NidecBrushless = 62. */ - public static final int kResourceType_NidecBrushless = 62; - /** kResourceType_CANifier = 63. */ - public static final int kResourceType_CANifier = 63; - /** kResourceType_TalonFX = 64. */ - public static final int kResourceType_TalonFX = 64; - /** kResourceType_CTRE_future1 = 65. */ - public static final int kResourceType_CTRE_future1 = 65; - /** kResourceType_CTRE_future2 = 66. */ - public static final int kResourceType_CTRE_future2 = 66; - /** kResourceType_CTRE_future3 = 67. */ - public static final int kResourceType_CTRE_future3 = 67; - /** kResourceType_CTRE_future4 = 68. */ - public static final int kResourceType_CTRE_future4 = 68; - /** kResourceType_CTRE_future5 = 69. */ - public static final int kResourceType_CTRE_future5 = 69; - /** kResourceType_CTRE_future6 = 70. */ - public static final int kResourceType_CTRE_future6 = 70; - /** kResourceType_LinearFilter = 71. */ - public static final int kResourceType_LinearFilter = 71; - /** kResourceType_XboxController = 72. */ - public static final int kResourceType_XboxController = 72; - /** kResourceType_UsbCamera = 73. */ - public static final int kResourceType_UsbCamera = 73; - /** kResourceType_NavX = 74. */ - public static final int kResourceType_NavX = 74; - /** kResourceType_Pixy = 75. */ - public static final int kResourceType_Pixy = 75; - /** kResourceType_Pixy2 = 76. */ - public static final int kResourceType_Pixy2 = 76; - /** kResourceType_ScanseSweep = 77. */ - public static final int kResourceType_ScanseSweep = 77; - /** kResourceType_Shuffleboard = 78. */ - public static final int kResourceType_Shuffleboard = 78; - /** kResourceType_CAN = 79. */ - public static final int kResourceType_CAN = 79; - /** kResourceType_DigilentDMC60 = 80. */ - public static final int kResourceType_DigilentDMC60 = 80; - /** kResourceType_PWMVictorSPX = 81. */ - public static final int kResourceType_PWMVictorSPX = 81; - /** kResourceType_RevSparkMaxPWM = 82. */ - public static final int kResourceType_RevSparkMaxPWM = 82; - /** kResourceType_RevSparkMaxCAN = 83. */ - public static final int kResourceType_RevSparkMaxCAN = 83; - /** kResourceType_ADIS16470 = 84. */ - public static final int kResourceType_ADIS16470 = 84; - /** kResourceType_PIDController2 = 85. */ - public static final int kResourceType_PIDController2 = 85; - /** kResourceType_ProfiledPIDController = 86. */ - public static final int kResourceType_ProfiledPIDController = 86; - /** kResourceType_Kinematics = 87. */ - public static final int kResourceType_Kinematics = 87; - /** kResourceType_Odometry = 88. */ - public static final int kResourceType_Odometry = 88; - /** kResourceType_Units = 89. */ - public static final int kResourceType_Units = 89; - /** kResourceType_TrapezoidProfile = 90. */ - public static final int kResourceType_TrapezoidProfile = 90; - /** kResourceType_DutyCycle = 91. */ - public static final int kResourceType_DutyCycle = 91; - /** kResourceType_AddressableLEDs = 92. */ - public static final int kResourceType_AddressableLEDs = 92; - /** kResourceType_FusionVenom = 93. */ - public static final int kResourceType_FusionVenom = 93; - /** kResourceType_CTRE_future7 = 94. */ - public static final int kResourceType_CTRE_future7 = 94; - /** kResourceType_CTRE_future8 = 95. */ - public static final int kResourceType_CTRE_future8 = 95; - /** kResourceType_CTRE_future9 = 96. */ - public static final int kResourceType_CTRE_future9 = 96; - /** kResourceType_CTRE_future10 = 97. */ - public static final int kResourceType_CTRE_future10 = 97; - /** kResourceType_CTRE_future11 = 98. */ - public static final int kResourceType_CTRE_future11 = 98; - /** kResourceType_CTRE_future12 = 99. */ - public static final int kResourceType_CTRE_future12 = 99; - /** kResourceType_CTRE_future13 = 100. */ - public static final int kResourceType_CTRE_future13 = 100; - /** kResourceType_CTRE_future14 = 101. */ - public static final int kResourceType_CTRE_future14 = 101; - /** kResourceType_ExponentialProfile = 102. */ - public static final int kResourceType_ExponentialProfile = 102; - /** kResourceType_PS4Controller = 103. */ - public static final int kResourceType_PS4Controller = 103; - /** kResourceType_PhotonCamera = 104. */ - public static final int kResourceType_PhotonCamera = 104; - /** kResourceType_PhotonPoseEstimator = 105. */ - public static final int kResourceType_PhotonPoseEstimator = 105; - /** kResourceType_PathPlannerPath = 106. */ - public static final int kResourceType_PathPlannerPath = 106; - /** kResourceType_PathPlannerAuto = 107. */ - public static final int kResourceType_PathPlannerAuto = 107; - /** kResourceType_PathFindingCommand = 108. */ - public static final int kResourceType_PathFindingCommand = 108; - /** kResourceType_Redux_future1 = 109. */ - public static final int kResourceType_Redux_future1 = 109; - /** kResourceType_Redux_future2 = 110. */ - public static final int kResourceType_Redux_future2 = 110; - /** kResourceType_Redux_future3 = 111. */ - public static final int kResourceType_Redux_future3 = 111; - /** kResourceType_Redux_future4 = 112. */ - public static final int kResourceType_Redux_future4 = 112; - /** kResourceType_Redux_future5 = 113. */ - public static final int kResourceType_Redux_future5 = 113; - /** kResourceType_RevSparkFlexCAN = 114. */ - public static final int kResourceType_RevSparkFlexCAN = 114; - /** kResourceType_RevSparkFlexPWM = 115. */ - public static final int kResourceType_RevSparkFlexPWM = 115; - /** kResourceType_BangBangController = 116. */ - public static final int kResourceType_BangBangController = 116; - /** kResourceType_DataLogManager = 117. */ - public static final int kResourceType_DataLogManager = 117; - /** kResourceType_LoggingFramework = 118. */ - public static final int kResourceType_LoggingFramework = 118; - /** kResourceType_ChoreoTrajectory = 119. */ - public static final int kResourceType_ChoreoTrajectory = 119; - /** kResourceType_ChoreoTrigger = 120. */ - public static final int kResourceType_ChoreoTrigger = 120; - /** kResourceType_PathWeaverTrajectory = 121. */ - public static final int kResourceType_PathWeaverTrajectory = 121; - /** kResourceType_Koors40 = 122. */ - public static final int kResourceType_Koors40 = 122; - /** kResourceType_ThriftyNova = 123. */ - public static final int kResourceType_ThriftyNova = 123; - /** kResourceType_RevServoHub = 124. */ - public static final int kResourceType_RevServoHub = 124; - /** kResourceType_PWFSEN36005 = 125. */ - public static final int kResourceType_PWFSEN36005 = 125; - /** kResourceType_LaserShark = 126. */ - public static final int kResourceType_LaserShark = 126; - } - - /** - * Instances from UsageReporting. - */ - @SuppressWarnings("TypeName") - public static final class tInstances { - private tInstances() { - } - - /** kLanguage_LabVIEW = 1. */ - public static final int kLanguage_LabVIEW = 1; - /** kLanguage_CPlusPlus = 2. */ - public static final int kLanguage_CPlusPlus = 2; - /** kLanguage_Java = 3. */ - public static final int kLanguage_Java = 3; - /** kLanguage_Python = 4. */ - public static final int kLanguage_Python = 4; - /** kLanguage_DotNet = 5. */ - public static final int kLanguage_DotNet = 5; - /** kLanguage_Kotlin = 6. */ - public static final int kLanguage_Kotlin = 6; - /** kLanguage_Rust = 7. */ - public static final int kLanguage_Rust = 7; - /** kCANPlugin_BlackJagBridge = 1. */ - public static final int kCANPlugin_BlackJagBridge = 1; - /** kCANPlugin_2CAN = 2. */ - public static final int kCANPlugin_2CAN = 2; - /** kFramework_Iterative = 1. */ - public static final int kFramework_Iterative = 1; - /** kFramework_Simple = 2. */ - public static final int kFramework_Simple = 2; - /** kFramework_CommandControl = 3. */ - public static final int kFramework_CommandControl = 3; - /** kFramework_Timed = 4. */ - public static final int kFramework_Timed = 4; - /** kFramework_ROS = 5. */ - public static final int kFramework_ROS = 5; - /** kFramework_RobotBuilder = 6. */ - public static final int kFramework_RobotBuilder = 6; - /** kFramework_AdvantageKit = 7. */ - public static final int kFramework_AdvantageKit = 7; - /** kFramework_MagicBot = 8. */ - public static final int kFramework_MagicBot = 8; - /** kRobotDrive_ArcadeStandard = 1. */ - public static final int kRobotDrive_ArcadeStandard = 1; - /** kRobotDrive_ArcadeButtonSpin = 2. */ - public static final int kRobotDrive_ArcadeButtonSpin = 2; - /** kRobotDrive_ArcadeRatioCurve = 3. */ - public static final int kRobotDrive_ArcadeRatioCurve = 3; - /** kRobotDrive_Tank = 4. */ - public static final int kRobotDrive_Tank = 4; - /** kRobotDrive_MecanumPolar = 5. */ - public static final int kRobotDrive_MecanumPolar = 5; - /** kRobotDrive_MecanumCartesian = 6. */ - public static final int kRobotDrive_MecanumCartesian = 6; - /** kRobotDrive2_DifferentialArcade = 7. */ - public static final int kRobotDrive2_DifferentialArcade = 7; - /** kRobotDrive2_DifferentialTank = 8. */ - public static final int kRobotDrive2_DifferentialTank = 8; - /** kRobotDrive2_DifferentialCurvature = 9. */ - public static final int kRobotDrive2_DifferentialCurvature = 9; - /** kRobotDrive2_MecanumCartesian = 10. */ - public static final int kRobotDrive2_MecanumCartesian = 10; - /** kRobotDrive2_MecanumPolar = 11. */ - public static final int kRobotDrive2_MecanumPolar = 11; - /** kRobotDrive2_KilloughCartesian = 12. */ - public static final int kRobotDrive2_KilloughCartesian = 12; - /** kRobotDrive2_KilloughPolar = 13. */ - public static final int kRobotDrive2_KilloughPolar = 13; - /** kRobotDriveSwerve_Other = 14. */ - public static final int kRobotDriveSwerve_Other = 14; - /** kRobotDriveSwerve_YAGSL = 15. */ - public static final int kRobotDriveSwerve_YAGSL = 15; - /** kRobotDriveSwerve_CTRE = 16. */ - public static final int kRobotDriveSwerve_CTRE = 16; - /** kRobotDriveSwerve_MaxSwerve = 17. */ - public static final int kRobotDriveSwerve_MaxSwerve = 17; - /** kRobotDriveSwerve_AdvantageKit = 18. */ - public static final int kRobotDriveSwerve_AdvantageKit = 18; - /** kDriverStationCIO_Analog = 1. */ - public static final int kDriverStationCIO_Analog = 1; - /** kDriverStationCIO_DigitalIn = 2. */ - public static final int kDriverStationCIO_DigitalIn = 2; - /** kDriverStationCIO_DigitalOut = 3. */ - public static final int kDriverStationCIO_DigitalOut = 3; - /** kDriverStationEIO_Acceleration = 1. */ - public static final int kDriverStationEIO_Acceleration = 1; - /** kDriverStationEIO_AnalogIn = 2. */ - public static final int kDriverStationEIO_AnalogIn = 2; - /** kDriverStationEIO_AnalogOut = 3. */ - public static final int kDriverStationEIO_AnalogOut = 3; - /** kDriverStationEIO_Button = 4. */ - public static final int kDriverStationEIO_Button = 4; - /** kDriverStationEIO_LED = 5. */ - public static final int kDriverStationEIO_LED = 5; - /** kDriverStationEIO_DigitalIn = 6. */ - public static final int kDriverStationEIO_DigitalIn = 6; - /** kDriverStationEIO_DigitalOut = 7. */ - public static final int kDriverStationEIO_DigitalOut = 7; - /** kDriverStationEIO_FixedDigitalOut = 8. */ - public static final int kDriverStationEIO_FixedDigitalOut = 8; - /** kDriverStationEIO_PWM = 9. */ - public static final int kDriverStationEIO_PWM = 9; - /** kDriverStationEIO_Encoder = 10. */ - public static final int kDriverStationEIO_Encoder = 10; - /** kDriverStationEIO_TouchSlider = 11. */ - public static final int kDriverStationEIO_TouchSlider = 11; - /** kADXL345_SPI = 1. */ - public static final int kADXL345_SPI = 1; - /** kADXL345_I2C = 2. */ - public static final int kADXL345_I2C = 2; - /** kCommand_Scheduler = 1. */ - public static final int kCommand_Scheduler = 1; - /** kCommand2_Scheduler = 2. */ - public static final int kCommand2_Scheduler = 2; - /** kSmartDashboard_Instance = 1. */ - public static final int kSmartDashboard_Instance = 1; - /** kSmartDashboard_LiveWindow = 2. */ - public static final int kSmartDashboard_LiveWindow = 2; - /** kKinematics_DifferentialDrive = 1. */ - public static final int kKinematics_DifferentialDrive = 1; - /** kKinematics_MecanumDrive = 2. */ - public static final int kKinematics_MecanumDrive = 2; - /** kKinematics_SwerveDrive = 3. */ - public static final int kKinematics_SwerveDrive = 3; - /** kOdometry_DifferentialDrive = 1. */ - public static final int kOdometry_DifferentialDrive = 1; - /** kOdometry_MecanumDrive = 2. */ - public static final int kOdometry_MecanumDrive = 2; - /** kOdometry_SwerveDrive = 3. */ - public static final int kOdometry_SwerveDrive = 3; - /** kDashboard_Unknown = 1. */ - public static final int kDashboard_Unknown = 1; - /** kDashboard_Glass = 2. */ - public static final int kDashboard_Glass = 2; - /** kDashboard_SmartDashboard = 3. */ - public static final int kDashboard_SmartDashboard = 3; - /** kDashboard_Shuffleboard = 4. */ - public static final int kDashboard_Shuffleboard = 4; - /** kDashboard_Elastic = 5. */ - public static final int kDashboard_Elastic = 5; - /** kDashboard_LabVIEW = 6. */ - public static final int kDashboard_LabVIEW = 6; - /** kDashboard_AdvantageScope = 7. */ - public static final int kDashboard_AdvantageScope = 7; - /** kDashboard_QFRCDashboard = 8. */ - public static final int kDashboard_QFRCDashboard = 8; - /** kDashboard_FRCWebComponents = 9. */ - public static final int kDashboard_FRCWebComponents = 9; - /** kDataLogLocation_Onboard = 1. */ - public static final int kDataLogLocation_Onboard = 1; - /** kDataLogLocation_USB = 2. */ - public static final int kDataLogLocation_USB = 2; - /** kLoggingFramework_Other = 1. */ - public static final int kLoggingFramework_Other = 1; - /** kLoggingFramework_Epilogue = 2. */ - public static final int kLoggingFramework_Epilogue = 2; - /** kLoggingFramework_Monologue = 3. */ - public static final int kLoggingFramework_Monologue = 3; - /** kLoggingFramework_AdvantageKit = 4. */ - public static final int kLoggingFramework_AdvantageKit = 4; - /** kLoggingFramework_DogLog = 5. */ - public static final int kLoggingFramework_DogLog = 5; - /** kPDP_CTRE = 1. */ - public static final int kPDP_CTRE = 1; - /** kPDP_REV = 2. */ - public static final int kPDP_REV = 2; - /** kPDP_Unknown = 3. */ - public static final int kPDP_Unknown = 3; - } - - /** Utility class. */ - private FRCNetComm() {} -} diff --git a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h deleted file mode 100644 index 65299cf91e..0000000000 --- a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h +++ /dev/null @@ -1,265 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -// THIS FILE WAS AUTO-GENERATED BY ./hal/generate_usage_reporting.py. DO NOT MODIFY - -#pragma once - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -// ifdef's definition is to allow for default parameters in C++. -#ifdef __cplusplus -/** - * Reports a hardware usage to the HAL. - * - * @param resource the used resource - * @param instanceNumber the instance of the resource - * @param context a user specified context index - * @param feature a user specified feature string - * @return the index of the added value in NetComm - */ -int64_t HAL_Report(int32_t resource, int32_t instanceNumber, - int32_t context = 0, const char* feature = nullptr); -#else - -/** - * Reports a hardware usage to the HAL. - * - * @param resource the used resource - * @param instanceNumber the instance of the resource - * @param context a user specified context index - * @param feature a user specified feature string - * @return the index of the added value in NetComm - */ -int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context, - const char* feature); -#endif - -#ifdef __cplusplus -} -#endif - -/* - * Autogenerated file! Do not manually edit this file. - */ - -#ifdef __cplusplus -namespace HALUsageReporting { - enum tResourceType : int32_t { - kResourceType_Controller = 0, - kResourceType_Module = 1, - kResourceType_Language = 2, - kResourceType_CANPlugin = 3, - kResourceType_Accelerometer = 4, - kResourceType_ADXL345 = 5, - kResourceType_AnalogChannel = 6, - kResourceType_AnalogTrigger = 7, - kResourceType_AnalogTriggerOutput = 8, - kResourceType_CANJaguar = 9, - kResourceType_Compressor = 10, - kResourceType_Counter = 11, - kResourceType_Dashboard = 12, - kResourceType_DigitalInput = 13, - kResourceType_DigitalOutput = 14, - kResourceType_DriverStationCIO = 15, - kResourceType_DriverStationEIO = 16, - kResourceType_DriverStationLCD = 17, - kResourceType_Encoder = 18, - kResourceType_GearTooth = 19, - kResourceType_Gyro = 20, - kResourceType_I2C = 21, - kResourceType_Framework = 22, - kResourceType_Jaguar = 23, - kResourceType_Joystick = 24, - kResourceType_Kinect = 25, - kResourceType_KinectStick = 26, - kResourceType_PIDController = 27, - kResourceType_Preferences = 28, - kResourceType_PWM = 29, - kResourceType_Relay = 30, - kResourceType_RobotDrive = 31, - kResourceType_SerialPort = 32, - kResourceType_Servo = 33, - kResourceType_Solenoid = 34, - kResourceType_SPI = 35, - kResourceType_Task = 36, - kResourceType_Ultrasonic = 37, - kResourceType_Victor = 38, - kResourceType_Button = 39, - kResourceType_Command = 40, - kResourceType_AxisCamera = 41, - kResourceType_PCVideoServer = 42, - kResourceType_SmartDashboard = 43, - kResourceType_Talon = 44, - kResourceType_HiTechnicColorSensor = 45, - kResourceType_HiTechnicAccel = 46, - kResourceType_HiTechnicCompass = 47, - kResourceType_SRF08 = 48, - kResourceType_AnalogOutput = 49, - kResourceType_VictorSP = 50, - kResourceType_PWMTalonSRX = 51, - kResourceType_CANTalonSRX = 52, - kResourceType_ADXL362 = 53, - kResourceType_ADXRS450 = 54, - kResourceType_RevSPARK = 55, - kResourceType_MindsensorsSD540 = 56, - kResourceType_DigitalGlitchFilter = 57, - kResourceType_ADIS16448 = 58, - kResourceType_PDP = 59, - kResourceType_PCM = 60, - kResourceType_PigeonIMU = 61, - kResourceType_NidecBrushless = 62, - kResourceType_CANifier = 63, - kResourceType_TalonFX = 64, - kResourceType_CTRE_future1 = 65, - kResourceType_CTRE_future2 = 66, - kResourceType_CTRE_future3 = 67, - kResourceType_CTRE_future4 = 68, - kResourceType_CTRE_future5 = 69, - kResourceType_CTRE_future6 = 70, - kResourceType_LinearFilter = 71, - kResourceType_XboxController = 72, - kResourceType_UsbCamera = 73, - kResourceType_NavX = 74, - kResourceType_Pixy = 75, - kResourceType_Pixy2 = 76, - kResourceType_ScanseSweep = 77, - kResourceType_Shuffleboard = 78, - kResourceType_CAN = 79, - kResourceType_DigilentDMC60 = 80, - kResourceType_PWMVictorSPX = 81, - kResourceType_RevSparkMaxPWM = 82, - kResourceType_RevSparkMaxCAN = 83, - kResourceType_ADIS16470 = 84, - kResourceType_PIDController2 = 85, - kResourceType_ProfiledPIDController = 86, - kResourceType_Kinematics = 87, - kResourceType_Odometry = 88, - kResourceType_Units = 89, - kResourceType_TrapezoidProfile = 90, - kResourceType_DutyCycle = 91, - kResourceType_AddressableLEDs = 92, - kResourceType_FusionVenom = 93, - kResourceType_CTRE_future7 = 94, - kResourceType_CTRE_future8 = 95, - kResourceType_CTRE_future9 = 96, - kResourceType_CTRE_future10 = 97, - kResourceType_CTRE_future11 = 98, - kResourceType_CTRE_future12 = 99, - kResourceType_CTRE_future13 = 100, - kResourceType_CTRE_future14 = 101, - kResourceType_ExponentialProfile = 102, - kResourceType_PS4Controller = 103, - kResourceType_PhotonCamera = 104, - kResourceType_PhotonPoseEstimator = 105, - kResourceType_PathPlannerPath = 106, - kResourceType_PathPlannerAuto = 107, - kResourceType_PathFindingCommand = 108, - kResourceType_Redux_future1 = 109, - kResourceType_Redux_future2 = 110, - kResourceType_Redux_future3 = 111, - kResourceType_Redux_future4 = 112, - kResourceType_Redux_future5 = 113, - kResourceType_RevSparkFlexCAN = 114, - kResourceType_RevSparkFlexPWM = 115, - kResourceType_BangBangController = 116, - kResourceType_DataLogManager = 117, - kResourceType_LoggingFramework = 118, - kResourceType_ChoreoTrajectory = 119, - kResourceType_ChoreoTrigger = 120, - kResourceType_PathWeaverTrajectory = 121, - kResourceType_Koors40 = 122, - kResourceType_ThriftyNova = 123, - kResourceType_RevServoHub = 124, - kResourceType_PWFSEN36005 = 125, - kResourceType_LaserShark = 126, - }; - enum tInstances : int32_t { - kLanguage_LabVIEW = 1, - kLanguage_CPlusPlus = 2, - kLanguage_Java = 3, - kLanguage_Python = 4, - kLanguage_DotNet = 5, - kLanguage_Kotlin = 6, - kLanguage_Rust = 7, - kCANPlugin_BlackJagBridge = 1, - kCANPlugin_2CAN = 2, - kFramework_Iterative = 1, - kFramework_Simple = 2, - kFramework_CommandControl = 3, - kFramework_Timed = 4, - kFramework_ROS = 5, - kFramework_RobotBuilder = 6, - kFramework_AdvantageKit = 7, - kFramework_MagicBot = 8, - kRobotDrive_ArcadeStandard = 1, - kRobotDrive_ArcadeButtonSpin = 2, - kRobotDrive_ArcadeRatioCurve = 3, - kRobotDrive_Tank = 4, - kRobotDrive_MecanumPolar = 5, - kRobotDrive_MecanumCartesian = 6, - kRobotDrive2_DifferentialArcade = 7, - kRobotDrive2_DifferentialTank = 8, - kRobotDrive2_DifferentialCurvature = 9, - kRobotDrive2_MecanumCartesian = 10, - kRobotDrive2_MecanumPolar = 11, - kRobotDrive2_KilloughCartesian = 12, - kRobotDrive2_KilloughPolar = 13, - kRobotDriveSwerve_Other = 14, - kRobotDriveSwerve_YAGSL = 15, - kRobotDriveSwerve_CTRE = 16, - kRobotDriveSwerve_MaxSwerve = 17, - kRobotDriveSwerve_AdvantageKit = 18, - kDriverStationCIO_Analog = 1, - kDriverStationCIO_DigitalIn = 2, - kDriverStationCIO_DigitalOut = 3, - kDriverStationEIO_Acceleration = 1, - kDriverStationEIO_AnalogIn = 2, - kDriverStationEIO_AnalogOut = 3, - kDriverStationEIO_Button = 4, - kDriverStationEIO_LED = 5, - kDriverStationEIO_DigitalIn = 6, - kDriverStationEIO_DigitalOut = 7, - kDriverStationEIO_FixedDigitalOut = 8, - kDriverStationEIO_PWM = 9, - kDriverStationEIO_Encoder = 10, - kDriverStationEIO_TouchSlider = 11, - kADXL345_SPI = 1, - kADXL345_I2C = 2, - kCommand_Scheduler = 1, - kCommand2_Scheduler = 2, - kSmartDashboard_Instance = 1, - kSmartDashboard_LiveWindow = 2, - kKinematics_DifferentialDrive = 1, - kKinematics_MecanumDrive = 2, - kKinematics_SwerveDrive = 3, - kOdometry_DifferentialDrive = 1, - kOdometry_MecanumDrive = 2, - kOdometry_SwerveDrive = 3, - kDashboard_Unknown = 1, - kDashboard_Glass = 2, - kDashboard_SmartDashboard = 3, - kDashboard_Shuffleboard = 4, - kDashboard_Elastic = 5, - kDashboard_LabVIEW = 6, - kDashboard_AdvantageScope = 7, - kDashboard_QFRCDashboard = 8, - kDashboard_FRCWebComponents = 9, - kDataLogLocation_Onboard = 1, - kDataLogLocation_USB = 2, - kLoggingFramework_Other = 1, - kLoggingFramework_Epilogue = 2, - kLoggingFramework_Monologue = 3, - kLoggingFramework_AdvantageKit = 4, - kLoggingFramework_DogLog = 5, - kPDP_CTRE = 1, - kPDP_REV = 2, - kPDP_Unknown = 3, - }; -} -#endif diff --git a/hal/src/generated/main/native/include/hal/UsageReporting.h b/hal/src/generated/main/native/include/hal/UsageReporting.h deleted file mode 100644 index e2fc6900d0..0000000000 --- a/hal/src/generated/main/native/include/hal/UsageReporting.h +++ /dev/null @@ -1,260 +0,0 @@ - -#ifndef __UsageReporting_h__ -#define __UsageReporting_h__ - -#ifdef _WIN32 -#include -#define EXPORT_FUNC __declspec(dllexport) __cdecl -#elif defined(__vxworks) -#include -#define EXPORT_FUNC -#else -#include -#include -#define EXPORT_FUNC -#endif - -#define kUsageReporting_version 1 - -namespace nUsageReporting -{ -typedef enum -{ - kResourceType_Controller = 0, - kResourceType_Module = 1, - kResourceType_Language = 2, - kResourceType_CANPlugin = 3, - kResourceType_Accelerometer = 4, - kResourceType_ADXL345 = 5, - kResourceType_AnalogChannel = 6, - kResourceType_AnalogTrigger = 7, - kResourceType_AnalogTriggerOutput = 8, - kResourceType_CANJaguar = 9, - kResourceType_Compressor = 10, - kResourceType_Counter = 11, - kResourceType_Dashboard = 12, - kResourceType_DigitalInput = 13, - kResourceType_DigitalOutput = 14, - kResourceType_DriverStationCIO = 15, - kResourceType_DriverStationEIO = 16, - kResourceType_DriverStationLCD = 17, - kResourceType_Encoder = 18, - kResourceType_GearTooth = 19, - kResourceType_Gyro = 20, - kResourceType_I2C = 21, - kResourceType_Framework = 22, - kResourceType_Jaguar = 23, - kResourceType_Joystick = 24, - kResourceType_Kinect = 25, - kResourceType_KinectStick = 26, - kResourceType_PIDController = 27, - kResourceType_Preferences = 28, - kResourceType_PWM = 29, - kResourceType_Relay = 30, - kResourceType_RobotDrive = 31, - kResourceType_SerialPort = 32, - kResourceType_Servo = 33, - kResourceType_Solenoid = 34, - kResourceType_SPI = 35, - kResourceType_Task = 36, - kResourceType_Ultrasonic = 37, - kResourceType_Victor = 38, - kResourceType_Button = 39, - kResourceType_Command = 40, - kResourceType_AxisCamera = 41, - kResourceType_PCVideoServer = 42, - kResourceType_SmartDashboard = 43, - kResourceType_Talon = 44, - kResourceType_HiTechnicColorSensor = 45, - kResourceType_HiTechnicAccel = 46, - kResourceType_HiTechnicCompass = 47, - kResourceType_SRF08 = 48, - kResourceType_AnalogOutput = 49, - kResourceType_VictorSP = 50, - kResourceType_PWMTalonSRX = 51, - kResourceType_CANTalonSRX = 52, - kResourceType_ADXL362 = 53, - kResourceType_ADXRS450 = 54, - kResourceType_RevSPARK = 55, - kResourceType_MindsensorsSD540 = 56, - kResourceType_DigitalGlitchFilter = 57, - kResourceType_ADIS16448 = 58, - kResourceType_PDP = 59, - kResourceType_PCM = 60, - kResourceType_PigeonIMU = 61, - kResourceType_NidecBrushless = 62, - kResourceType_CANifier = 63, - kResourceType_TalonFX = 64, - kResourceType_CTRE_future1 = 65, - kResourceType_CTRE_future2 = 66, - kResourceType_CTRE_future3 = 67, - kResourceType_CTRE_future4 = 68, - kResourceType_CTRE_future5 = 69, - kResourceType_CTRE_future6 = 70, - kResourceType_LinearFilter = 71, - kResourceType_XboxController = 72, - kResourceType_UsbCamera = 73, - kResourceType_NavX = 74, - kResourceType_Pixy = 75, - kResourceType_Pixy2 = 76, - kResourceType_ScanseSweep = 77, - kResourceType_Shuffleboard = 78, - kResourceType_CAN = 79, - kResourceType_DigilentDMC60 = 80, - kResourceType_PWMVictorSPX = 81, - kResourceType_RevSparkMaxPWM = 82, - kResourceType_RevSparkMaxCAN = 83, - kResourceType_ADIS16470 = 84, - kResourceType_PIDController2 = 85, - kResourceType_ProfiledPIDController = 86, - kResourceType_Kinematics = 87, - kResourceType_Odometry = 88, - kResourceType_Units = 89, - kResourceType_TrapezoidProfile = 90, - kResourceType_DutyCycle = 91, - kResourceType_AddressableLEDs = 92, - kResourceType_FusionVenom = 93, - kResourceType_CTRE_future7 = 94, - kResourceType_CTRE_future8 = 95, - kResourceType_CTRE_future9 = 96, - kResourceType_CTRE_future10 = 97, - kResourceType_CTRE_future11 = 98, - kResourceType_CTRE_future12 = 99, - kResourceType_CTRE_future13 = 100, - kResourceType_CTRE_future14 = 101, - kResourceType_ExponentialProfile = 102, - kResourceType_PS4Controller = 103, - kResourceType_PhotonCamera = 104, - kResourceType_PhotonPoseEstimator = 105, - kResourceType_PathPlannerPath = 106, - kResourceType_PathPlannerAuto = 107, - kResourceType_PathFindingCommand = 108, - kResourceType_Redux_future1 = 109, - kResourceType_Redux_future2 = 110, - kResourceType_Redux_future3 = 111, - kResourceType_Redux_future4 = 112, - kResourceType_Redux_future5 = 113, - kResourceType_RevSparkFlexCAN = 114, - kResourceType_RevSparkFlexPWM = 115, - kResourceType_BangBangController = 116, - kResourceType_DataLogManager = 117, - kResourceType_LoggingFramework = 118, - kResourceType_ChoreoTrajectory = 119, - kResourceType_ChoreoTrigger = 120, - kResourceType_PathWeaverTrajectory = 121, - kResourceType_Koors40 = 122, - kResourceType_ThriftyNova = 123, - kResourceType_RevServoHub = 124, - kResourceType_PWFSEN36005 = 125, - kResourceType_LaserShark = 126, - -// kResourceType_MaximumID = 255, -} tResourceType; - -typedef enum -{ - kLanguage_LabVIEW = 1, - kLanguage_CPlusPlus = 2, - kLanguage_Java = 3, - kLanguage_Python = 4, - kLanguage_DotNet = 5, - kLanguage_Kotlin = 6, - kLanguage_Rust = 7, - kCANPlugin_BlackJagBridge = 1, - kCANPlugin_2CAN = 2, - kFramework_Iterative = 1, - kFramework_Simple = 2, - kFramework_CommandControl = 3, - kFramework_Timed = 4, - kFramework_ROS = 5, - kFramework_RobotBuilder = 6, - kFramework_AdvantageKit = 7, - kFramework_MagicBot = 8, - kRobotDrive_ArcadeStandard = 1, - kRobotDrive_ArcadeButtonSpin = 2, - kRobotDrive_ArcadeRatioCurve = 3, - kRobotDrive_Tank = 4, - kRobotDrive_MecanumPolar = 5, - kRobotDrive_MecanumCartesian = 6, - kRobotDrive2_DifferentialArcade = 7, - kRobotDrive2_DifferentialTank = 8, - kRobotDrive2_DifferentialCurvature = 9, - kRobotDrive2_MecanumCartesian = 10, - kRobotDrive2_MecanumPolar = 11, - kRobotDrive2_KilloughCartesian = 12, - kRobotDrive2_KilloughPolar = 13, - kRobotDriveSwerve_Other = 14, - kRobotDriveSwerve_YAGSL = 15, - kRobotDriveSwerve_CTRE = 16, - kRobotDriveSwerve_MaxSwerve = 17, - kRobotDriveSwerve_AdvantageKit = 18, - kDriverStationCIO_Analog = 1, - kDriverStationCIO_DigitalIn = 2, - kDriverStationCIO_DigitalOut = 3, - kDriverStationEIO_Acceleration = 1, - kDriverStationEIO_AnalogIn = 2, - kDriverStationEIO_AnalogOut = 3, - kDriverStationEIO_Button = 4, - kDriverStationEIO_LED = 5, - kDriverStationEIO_DigitalIn = 6, - kDriverStationEIO_DigitalOut = 7, - kDriverStationEIO_FixedDigitalOut = 8, - kDriverStationEIO_PWM = 9, - kDriverStationEIO_Encoder = 10, - kDriverStationEIO_TouchSlider = 11, - kADXL345_SPI = 1, - kADXL345_I2C = 2, - kCommand_Scheduler = 1, - kCommand2_Scheduler = 2, - kSmartDashboard_Instance = 1, - kSmartDashboard_LiveWindow = 2, - kKinematics_DifferentialDrive = 1, - kKinematics_MecanumDrive = 2, - kKinematics_SwerveDrive = 3, - kOdometry_DifferentialDrive = 1, - kOdometry_MecanumDrive = 2, - kOdometry_SwerveDrive = 3, - kDashboard_Unknown = 1, - kDashboard_Glass = 2, - kDashboard_SmartDashboard = 3, - kDashboard_Shuffleboard = 4, - kDashboard_Elastic = 5, - kDashboard_LabVIEW = 6, - kDashboard_AdvantageScope = 7, - kDashboard_QFRCDashboard = 8, - kDashboard_FRCWebComponents = 9, - kDataLogLocation_Onboard = 1, - kDataLogLocation_USB = 2, - kLoggingFramework_Other = 1, - kLoggingFramework_Epilogue = 2, - kLoggingFramework_Monologue = 3, - kLoggingFramework_AdvantageKit = 4, - kLoggingFramework_DogLog = 5, - kPDP_CTRE = 1, - kPDP_REV = 2, - kPDP_Unknown = 3, -} tInstances; - -/** - * Report the usage of a resource of interest. - * - * @param resource one of the values in the tResourceType above (max value 51). - * @param instanceNumber an index that identifies the resource instance. - * @param context an optional additional context number for some cases (such as module number). Set to 0 to omit. - * @param feature a string to be included describing features in use on a specific resource. Setting the same resource more than once allows you to change the feature string. - */ -uint32_t EXPORT_FUNC report(tResourceType resource, uint8_t instanceNumber, uint8_t context = 0, const char* feature = NULL); -} // namespace nUsageReporting - -#ifdef __cplusplus -extern "C" -{ -#endif - - uint32_t EXPORT_FUNC FRC_NetworkCommunication_nUsageReporting_report(uint8_t resource, uint8_t instanceNumber, uint8_t context, const char* feature); - -#ifdef __cplusplus -} -#endif - -#endif // __UsageReporting_h__ diff --git a/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java b/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java index 580dcd1d32..3be77953e6 100644 --- a/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java @@ -10,7 +10,6 @@ import java.nio.ByteBuffer; * Driver Station JNI Functions. * * @see "hal/DriverStation.h" - * @see "hal/FRCUsageReporting.h" */ public class DriverStationJNI extends JNIWrapper { /** @@ -62,53 +61,6 @@ public class DriverStationJNI extends JNIWrapper { */ public static native void observeUserProgramTest(); - /** - * Report the usage of a resource of interest. - * - *

Original signature: uint32_t report(tResourceType, uint8_t, uint8_t, const - * char*) - * - * @param resource one of the values in the tResourceType above. - * @param instanceNumber an index that identifies the resource instance. - * @see "HAL_Report" - */ - public static void report(int resource, int instanceNumber) { - report(resource, instanceNumber, 0, ""); - } - - /** - * Report the usage of a resource of interest. - * - *

Original signature: uint32_t report(tResourceType, uint8_t, uint8_t, const - * char*) - * - * @param resource one of the values in the tResourceType above. - * @param instanceNumber an index that identifies the resource instance. - * @param context an optional additional context number for some cases (such as module number). - * Set to 0 to omit. - * @see "HAL_Report" - */ - public static void report(int resource, int instanceNumber, int context) { - report(resource, instanceNumber, context, ""); - } - - /** - * Report the usage of a resource of interest. - * - *

Original signature: uint32_t report(tResourceType, uint8_t, uint8_t, const - * char*) - * - * @param resource one of the values in the tResourceType above. - * @param instanceNumber an index that identifies the resource instance. - * @param context an optional additional context number for some cases (such as module number). - * Set to 0 to omit. - * @param feature a string to be included describing features in use on a specific resource. - * Setting the same resource more than once allows you to change the feature string. - * @return the index of the added value in NetComm - * @see "HAL_Report" - */ - public static native int report(int resource, int instanceNumber, int context, String feature); - /** * Gets the current control word of the driver station. * diff --git a/hal/src/main/java/edu/wpi/first/hal/HAL.java b/hal/src/main/java/edu/wpi/first/hal/HAL.java index e551ffff16..485c4a36c1 100644 --- a/hal/src/main/java/edu/wpi/first/hal/HAL.java +++ b/hal/src/main/java/edu/wpi/first/hal/HAL.java @@ -12,7 +12,7 @@ import java.util.List; * * @see "hal/HALBase.h" * @see "hal/Main.h" - * @see "hal/FRCUsageReporting.h" + * @see "hal/UsageReporting.h" */ public final class HAL extends JNIWrapper { /** @@ -212,52 +212,28 @@ public final class HAL extends JNIWrapper { public static native boolean getSystemTimeValid(); /** - * Report the usage of a resource of interest. + * Reports usage of a resource of interest. Repeated calls for the same resource name replace the + * previous report. * - *

Original signature: uint32_t report(tResourceType, uint8_t, uint8_t, const - * char*) - * - * @param resource one of the values in the tResourceType above. - * @param instanceNumber an index that identifies the resource instance. - * @see "HAL_Report" + * @param resource the used resource name + * @param data arbitrary associated data string + * @return a handle */ - public static void report(int resource, int instanceNumber) { - report(resource, instanceNumber, 0, ""); + public static int reportUsage(String resource, String data) { + return UsageReportingJNI.report(resource, data); } /** - * Report the usage of a resource of interest. + * Reports usage of a resource of interest. Repeated calls for the same resource name replace the + * previous report. * - *

Original signature: uint32_t report(tResourceType, uint8_t, uint8_t, const - * char*) - * - * @param resource one of the values in the tResourceType above. - * @param instanceNumber an index that identifies the resource instance. - * @param context an optional additional context number for some cases (such as module number). - * Set to 0 to omit. - * @see "HAL_Report" + * @param resource the used resource name + * @param instanceNumber an index that identifies the resource instance + * @param data arbitrary associated data string + * @return a handle */ - public static void report(int resource, int instanceNumber, int context) { - report(resource, instanceNumber, context, ""); - } - - /** - * Report the usage of a resource of interest. - * - *

Original signature: uint32_t report(tResourceType, uint8_t, uint8_t, const - * char*) - * - * @param resource one of the values in the tResourceType above. - * @param instanceNumber an index that identifies the resource instance. - * @param context an optional additional context number for some cases (such as module number). - * Set to 0 to omit. - * @param feature a string to be included describing features in use on a specific resource. - * Setting the same resource more than once allows you to change the feature string. - * @return the index of the added value in NetComm - * @see "HAL_Report" - */ - public static int report(int resource, int instanceNumber, int context, String feature) { - return DriverStationJNI.report(resource, instanceNumber, context, feature); + public static int reportUsage(String resource, int instanceNumber, String data) { + return reportUsage(resource + "[" + instanceNumber + "]", data); } private HAL() {} diff --git a/hal/src/main/java/edu/wpi/first/hal/UsageReportingJNI.java b/hal/src/main/java/edu/wpi/first/hal/UsageReportingJNI.java new file mode 100644 index 0000000000..12db0a57ee --- /dev/null +++ b/hal/src/main/java/edu/wpi/first/hal/UsageReportingJNI.java @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.hal; + +/** + * Usage Reporting JNI Functions. + * + * @see "hal/UsageReporting.h" + */ +public class UsageReportingJNI extends JNIWrapper { + /** + * Reports usage of a resource of interest. Repeated calls for the same resource name replace the + * previous report. + * + * @param resource the used resource name + * @param data arbitrary associated data string + * @return a handle + */ + public static native int report(String resource, String data); + + /** Utility class. */ + private UsageReportingJNI() {} +} diff --git a/hal/src/main/native/cpp/UsageReporting.cpp b/hal/src/main/native/cpp/UsageReporting.cpp new file mode 100644 index 0000000000..d4693888d9 --- /dev/null +++ b/hal/src/main/native/cpp/UsageReporting.cpp @@ -0,0 +1,12 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "hal/UsageReporting.h" + +#include + +int32_t HAL_ReportUsage(std::string_view resource, int instanceNumber, + std::string_view data) { + return HAL_ReportUsage(fmt::format("{}[{}]", resource, instanceNumber), data); +} diff --git a/hal/src/main/native/cpp/jni/DriverStationJNI.cpp b/hal/src/main/native/cpp/jni/DriverStationJNI.cpp index 87c8b14505..f370c0637c 100644 --- a/hal/src/main/native/cpp/jni/DriverStationJNI.cpp +++ b/hal/src/main/native/cpp/jni/DriverStationJNI.cpp @@ -12,7 +12,6 @@ #include "HALUtil.h" #include "edu_wpi_first_hal_DriverStationJNI.h" #include "hal/DriverStation.h" -#include "hal/FRCUsageReporting.h" #include "hal/HALBase.h" static_assert(edu_wpi_first_hal_DriverStationJNI_kUnknownAllianceStation == @@ -102,22 +101,6 @@ Java_edu_wpi_first_hal_DriverStationJNI_observeUserProgramTest HAL_ObserveUserProgramTest(); } -/* - * Class: edu_wpi_first_hal_DriverStationJNI - * Method: report - * Signature: (IIILjava/lang/String;)I - */ -JNIEXPORT jint JNICALL -Java_edu_wpi_first_hal_DriverStationJNI_report - (JNIEnv* paramEnv, jclass, jint paramResource, jint paramInstanceNumber, - jint paramContext, jstring paramFeature) -{ - JStringRef featureStr{paramEnv, paramFeature}; - jint returnValue = HAL_Report(paramResource, paramInstanceNumber, - paramContext, featureStr.c_str()); - return returnValue; -} - /* * Class: edu_wpi_first_hal_DriverStationJNI * Method: nativeGetControlWord diff --git a/hal/src/main/native/cpp/jni/UsageReportingJNI.cpp b/hal/src/main/native/cpp/jni/UsageReportingJNI.cpp new file mode 100644 index 0000000000..272770f6d1 --- /dev/null +++ b/hal/src/main/native/cpp/jni/UsageReportingJNI.cpp @@ -0,0 +1,35 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include + +#include +#include + +#include "edu_wpi_first_hal_UsageReportingJNI.h" +#include "hal/UsageReporting.h" + +using namespace wpi::java; + +extern "C" { + +/* + * Class: edu_wpi_first_hal_UsageReportingJNI + * Method: report + * Signature: (Ljava/lang/String;Ljava/lang/String;)I + */ +JNIEXPORT jint JNICALL +Java_edu_wpi_first_hal_UsageReportingJNI_report + (JNIEnv* env, jclass, jstring resource, jstring data) +{ + JStringRef resourceStr{env, resource}; + JStringRef dataStr{env, data}; + WPI_String resourceWpiStr = wpi::make_string(resourceStr); + WPI_String dataWpiStr = wpi::make_string(dataStr); + return HAL_ReportUsage(&resourceWpiStr, &dataWpiStr); +} + +} // extern "C" diff --git a/hal/src/main/native/include/hal/HAL.h b/hal/src/main/native/include/hal/HAL.h index 01af5ea82e..afadadbbc4 100644 --- a/hal/src/main/native/include/hal/HAL.h +++ b/hal/src/main/native/include/hal/HAL.h @@ -16,7 +16,6 @@ #include "hal/DriverStation.h" #include "hal/Encoder.h" #include "hal/Errors.h" -#include "hal/FRCUsageReporting.h" #include "hal/HALBase.h" #include "hal/I2C.h" #include "hal/LEDs.h" @@ -29,4 +28,5 @@ #include "hal/SimDevice.h" #include "hal/Threads.h" #include "hal/Types.h" +#include "hal/UsageReporting.h" #include "hal/Value.h" diff --git a/hal/src/main/native/include/hal/UsageReporting.h b/hal/src/main/native/include/hal/UsageReporting.h new file mode 100644 index 0000000000..b0971e1000 --- /dev/null +++ b/hal/src/main/native/include/hal/UsageReporting.h @@ -0,0 +1,66 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +#ifdef __cplusplus +#include +#endif + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * Reports usage of a resource of interest. Repeated calls for the same + * resource name replace the previous report. + * + * @param resource the used resource name; convention is to suffix with + * "[instanceNum]" for multiple instances of the same + * resource + * @param data arbitrary associated data string + * @return a handle + */ +int32_t HAL_ReportUsage(const struct WPI_String* resource, + const struct WPI_String* data); + +#ifdef __cplusplus +} // extern "C" +#endif + +#ifdef __cplusplus +/** + * Reports usage of a resource of interest. Repeated calls for the same + * resource name replace the previous report. + * + * @param resource the used resource name; convention is to suffix with + * "[instanceNum]" for multiple instances of the same + * resource + * @param data arbitrary associated data string + * @return a handle + */ +inline int32_t HAL_ReportUsage(std::string_view resource, + std::string_view data) { + WPI_String resourceStr = wpi::make_string(resource); + WPI_String dataStr = wpi::make_string(data); + return HAL_ReportUsage(&resourceStr, &dataStr); +} + +/** + * Reports usage of a resource of interest. Repeated calls for the same + * resource name replace the previous report. + * + * @param resource the used resource name + * @param instanceNumber an index that identifies the resource instance + * @param data arbitrary associated data string + * @return a handle + */ +int32_t HAL_ReportUsage(std::string_view resource, int instanceNumber, + std::string_view data); + +#endif diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp index 16ef13c7c7..df9368803a 100644 --- a/hal/src/main/native/sim/HAL.cpp +++ b/hal/src/main/native/sim/HAL.cpp @@ -458,8 +458,8 @@ void HALSIM_CancelAllSimPeriodicCallbacks(void) { gSimPeriodicAfter.Reset(); } -int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context, - const char* feature) { +int32_t HAL_ReportUsage(const struct WPI_String* resource, + const struct WPI_String* data) { return 0; // Do nothing for now } diff --git a/hal/src/main/native/systemcore/HAL.cpp b/hal/src/main/native/systemcore/HAL.cpp index 171e4635ee..887ae0823d 100644 --- a/hal/src/main/native/systemcore/HAL.cpp +++ b/hal/src/main/native/systemcore/HAL.cpp @@ -70,6 +70,7 @@ void InitializeHAL() { InitializeSerialPort(); InitializeSmartIo(); InitializeThreads(); + InitializeUsageReporting(); } } // namespace init @@ -343,16 +344,4 @@ void HAL_SimPeriodicBefore(void) {} void HAL_SimPeriodicAfter(void) {} -int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context, - const char* feature) { - if (feature == nullptr) { - feature = ""; - } - - return 0; - - // return FRC_NetworkCommunication_nUsageReporting_report( - // resource, instanceNumber, context, feature); -} - } // extern "C" diff --git a/hal/src/main/native/systemcore/HALInitializer.h b/hal/src/main/native/systemcore/HALInitializer.h index ba0bc0eaf5..bee47fd29b 100644 --- a/hal/src/main/native/systemcore/HALInitializer.h +++ b/hal/src/main/native/systemcore/HALInitializer.h @@ -43,4 +43,5 @@ extern void InitializePWM(); extern void InitializeSerialPort(); extern void InitializeSmartIo(); extern void InitializeThreads(); +extern void InitializeUsageReporting(); } // namespace hal::init diff --git a/hal/src/main/native/systemcore/UsageReporting.cpp b/hal/src/main/native/systemcore/UsageReporting.cpp new file mode 100644 index 0000000000..e7bd0805c1 --- /dev/null +++ b/hal/src/main/native/systemcore/UsageReporting.cpp @@ -0,0 +1,51 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include +#include +#include +#include +#include + +#include "SystemServerInternal.h" + +namespace { +struct SystemServerUsageReporting { + nt::NetworkTableInstance ntInst; + wpi::StringMap publishers; + + explicit SystemServerUsageReporting(nt::NetworkTableInstance inst) + : ntInst{inst} {} +}; + +} // namespace + +static ::SystemServerUsageReporting* systemServerUsage; + +extern "C" { + +int32_t HAL_ReportUsage(const struct WPI_String* resource, + const struct WPI_String* data) { + auto resourceStr = wpi::to_string_view(resource); + auto& publisher = systemServerUsage->publishers[resourceStr]; + if (!publisher) { + publisher = + systemServerUsage->ntInst + .GetStringTopic(fmt::format("/UsageReporting/{}", resourceStr)) + .Publish(); + } + publisher.Set(wpi::to_string_view(data)); + + return 0; +} + +} // extern "C" + +namespace hal::init { +void InitializeUsageReporting() { + systemServerUsage = new ::SystemServerUsageReporting{hal::GetSystemServer()}; +} +} // namespace hal::init diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java index 34319caa07..299e07c56e 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java @@ -6,8 +6,6 @@ package edu.wpi.first.wpilibj2.command; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -99,7 +97,7 @@ public final class CommandScheduler implements Sendable, AutoCloseable { private final Watchdog m_watchdog = new Watchdog(TimedRobot.kDefaultPeriod, () -> {}); CommandScheduler() { - HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand2_Scheduler); + HAL.reportUsage("CommandScheduler", ""); SendableRegistry.add(this, "Scheduler"); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp index b077de5e53..c6c61a46ad 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -13,8 +13,8 @@ #include #include #include -#include #include +#include #include #include #include @@ -69,8 +69,7 @@ CommandScheduler::CommandScheduler() : m_impl(new Impl), m_watchdog(frc::TimedRobot::kDefaultPeriod, [] { std::puts("CommandScheduler loop time overrun."); }) { - HAL_Report(HALUsageReporting::kResourceType_Command, - HALUsageReporting::kCommand2_Scheduler); + HAL_ReportUsage("CommandScheduler", ""); wpi::SendableRegistry::Add(this, "Scheduler"); } diff --git a/wpilibc/src/generate/main/native/cpp/hid.cpp.jinja b/wpilibc/src/generate/main/native/cpp/hid.cpp.jinja index 77b198a800..d590b55db0 100644 --- a/wpilibc/src/generate/main/native/cpp/hid.cpp.jinja +++ b/wpilibc/src/generate/main/native/cpp/hid.cpp.jinja @@ -8,7 +8,7 @@ {%- endmacro %} #include "frc/{{ ConsoleName }}Controller.h" -#include +#include #include #include "frc/event/BooleanEvent.h" @@ -16,7 +16,7 @@ using namespace frc; {{ ConsoleName }}Controller::{{ ConsoleName }}Controller(int port) : GenericHID(port) { - {{ "// " if SkipReporting }}HAL_Report(HALUsageReporting::kResourceType_{{ ConsoleName }}Controller, port + 1); + HAL_ReportUsage("HID", port, "{{ ConsoleName }}Controller"); } {% for stick in sticks %} double {{ ConsoleName }}Controller::Get{{ stick.NameParts|map("capitalize")|join }}() const { diff --git a/wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja b/wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja index ef995546ac..84cb1a4e4a 100644 --- a/wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja +++ b/wpilibc/src/generate/main/native/cpp/motorcontroller/pwm_motor_controller.cpp.jinja @@ -6,7 +6,7 @@ #include "frc/motorcontrol/{{ name }}.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ using namespace frc; m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_{{ ResourceName }}, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "{{ ResourceName }}"); } diff --git a/wpilibc/src/generated/main/native/cpp/PS4Controller.cpp b/wpilibc/src/generated/main/native/cpp/PS4Controller.cpp index 1b2b88b182..548df741b9 100644 --- a/wpilibc/src/generated/main/native/cpp/PS4Controller.cpp +++ b/wpilibc/src/generated/main/native/cpp/PS4Controller.cpp @@ -6,7 +6,7 @@ #include "frc/PS4Controller.h" -#include +#include #include #include "frc/event/BooleanEvent.h" @@ -14,7 +14,7 @@ using namespace frc; PS4Controller::PS4Controller(int port) : GenericHID(port) { - HAL_Report(HALUsageReporting::kResourceType_PS4Controller, port + 1); + HAL_ReportUsage("HID", port, "PS4Controller"); } double PS4Controller::GetLeftX() const { diff --git a/wpilibc/src/generated/main/native/cpp/PS5Controller.cpp b/wpilibc/src/generated/main/native/cpp/PS5Controller.cpp index 56d50e37ee..bfb3ff211f 100644 --- a/wpilibc/src/generated/main/native/cpp/PS5Controller.cpp +++ b/wpilibc/src/generated/main/native/cpp/PS5Controller.cpp @@ -6,7 +6,7 @@ #include "frc/PS5Controller.h" -#include +#include #include #include "frc/event/BooleanEvent.h" @@ -14,7 +14,7 @@ using namespace frc; PS5Controller::PS5Controller(int port) : GenericHID(port) { - // HAL_Report(HALUsageReporting::kResourceType_PS5Controller, port + 1); + HAL_ReportUsage("HID", port, "PS5Controller"); } double PS5Controller::GetLeftX() const { diff --git a/wpilibc/src/generated/main/native/cpp/StadiaController.cpp b/wpilibc/src/generated/main/native/cpp/StadiaController.cpp index ee87b888df..51a25c3b88 100644 --- a/wpilibc/src/generated/main/native/cpp/StadiaController.cpp +++ b/wpilibc/src/generated/main/native/cpp/StadiaController.cpp @@ -6,7 +6,7 @@ #include "frc/StadiaController.h" -#include +#include #include #include "frc/event/BooleanEvent.h" @@ -14,7 +14,7 @@ using namespace frc; StadiaController::StadiaController(int port) : GenericHID(port) { - // HAL_Report(HALUsageReporting::kResourceType_StadiaController, port + 1); + HAL_ReportUsage("HID", port, "StadiaController"); } double StadiaController::GetLeftX() const { diff --git a/wpilibc/src/generated/main/native/cpp/XboxController.cpp b/wpilibc/src/generated/main/native/cpp/XboxController.cpp index 4b220170a6..f4de6f93d7 100644 --- a/wpilibc/src/generated/main/native/cpp/XboxController.cpp +++ b/wpilibc/src/generated/main/native/cpp/XboxController.cpp @@ -6,7 +6,7 @@ #include "frc/XboxController.h" -#include +#include #include #include "frc/event/BooleanEvent.h" @@ -14,7 +14,7 @@ using namespace frc; XboxController::XboxController(int port) : GenericHID(port) { - HAL_Report(HALUsageReporting::kResourceType_XboxController, port + 1); + HAL_ReportUsage("HID", port, "XboxController"); } double XboxController::GetLeftX() const { diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp index 72eac176fd..3a81b5f1a4 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/DMC60.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/DMC60.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ DMC60::DMC60(int channel) : PWMMotorController("DMC60", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_DigilentDMC60, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "DigilentDMC60"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp index 348ff568df..78d11b0637 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Jaguar.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/Jaguar.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ Jaguar::Jaguar(int channel) : PWMMotorController("Jaguar", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_Jaguar, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "Jaguar"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/Koors40.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Koors40.cpp index 023e51a404..3ae766358b 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/Koors40.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Koors40.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/Koors40.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ Koors40::Koors40(int channel) : PWMMotorController("Koors40", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_Koors40, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "Koors40"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkFlex.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkFlex.cpp index 500757ee35..4fe3360139 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkFlex.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkFlex.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/PWMSparkFlex.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ PWMSparkFlex::PWMSparkFlex(int channel) : PWMMotorController("PWMSparkFlex", cha m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_RevSparkFlexPWM, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "RevSparkFlexPWM"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkMax.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkMax.cpp index 870b568f16..8d42961646 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkMax.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMSparkMax.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/PWMSparkMax.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ PWMSparkMax::PWMSparkMax(int channel) : PWMMotorController("PWMSparkMax", channe m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_RevSparkMaxPWM, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "RevSparkMaxPWM"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonFX.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonFX.cpp index d9cd881214..2f45a99e5a 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonFX.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonFX.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/PWMTalonFX.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ PWMTalonFX::PWMTalonFX(int channel) : PWMMotorController("PWMTalonFX", channel) m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_TalonFX, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "TalonFX"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonSRX.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonSRX.cpp index 5df4050743..5a33d0aa41 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonSRX.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMTalonSRX.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/PWMTalonSRX.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ PWMTalonSRX::PWMTalonSRX(int channel) : PWMMotorController("PWMTalonSRX", channe m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_PWMTalonSRX, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "PWMTalonSRX"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVenom.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVenom.cpp index 451e1f35e7..f7c8a82c34 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVenom.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVenom.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/PWMVenom.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ PWMVenom::PWMVenom(int channel) : PWMMotorController("PWMVenom", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_FusionVenom, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "FusionVenom"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVictorSPX.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVictorSPX.cpp index c759808a9d..1a29ac7367 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVictorSPX.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/PWMVictorSPX.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/PWMVictorSPX.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ PWMVictorSPX::PWMVictorSPX(int channel) : PWMMotorController("PWMVictorSPX", cha m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_PWMVictorSPX, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "PWMVictorSPX"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp index c39e77f63f..1e7e1fd3d1 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/SD540.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/SD540.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ SD540::SD540(int channel) : PWMMotorController("SD540", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "MindsensorsSD540"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/Spark.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Spark.cpp index 4f2e078722..8cea7e8fe0 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/Spark.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Spark.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/Spark.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ Spark::Spark(int channel) : PWMMotorController("Spark", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_RevSPARK, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "RevSPARK"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/SparkMini.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/SparkMini.cpp index 450653e6b8..d04fd3d6ae 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/SparkMini.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/SparkMini.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/SparkMini.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ SparkMini::SparkMini(int channel) : PWMMotorController("SparkMini", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_RevSPARK, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "RevSPARK"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/Talon.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Talon.cpp index 9e81d2885c..576d8e278f 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/Talon.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Talon.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/Talon.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ Talon::Talon(int channel) : PWMMotorController("Talon", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_Talon, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "Talon"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp index 7062518bef..d197baba20 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/Victor.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/Victor.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ Victor::Victor(int channel) : PWMMotorController("Victor", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_Victor, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "Victor"); } diff --git a/wpilibc/src/generated/main/native/cpp/motorcontrol/VictorSP.cpp b/wpilibc/src/generated/main/native/cpp/motorcontrol/VictorSP.cpp index f8bc126093..a3915860c8 100644 --- a/wpilibc/src/generated/main/native/cpp/motorcontrol/VictorSP.cpp +++ b/wpilibc/src/generated/main/native/cpp/motorcontrol/VictorSP.cpp @@ -6,7 +6,7 @@ #include "frc/motorcontrol/VictorSP.h" -#include +#include using namespace frc; @@ -16,5 +16,5 @@ VictorSP::VictorSP(int channel) : PWMMotorController("VictorSP", channel) { m_pwm.SetSpeed(0.0); m_pwm.SetZeroLatch(); - HAL_Report(HALUsageReporting::kResourceType_VictorSP, GetChannel() + 1); + HAL_ReportUsage("IO", GetChannel(), "VictorSP"); } diff --git a/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp index 1fdf71ed37..38fa4b71f8 100644 --- a/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp +++ b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp @@ -4,7 +4,7 @@ #include "frc/ADXL345_I2C.h" -#include +#include #include #include #include @@ -27,8 +27,9 @@ ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress) // Specify the data format to read SetRange(range); - HAL_Report(HALUsageReporting::kResourceType_ADXL345, - HALUsageReporting::kADXL345_I2C, 0); + HAL_ReportUsage( + fmt::format("I2C[{}][{}]", static_cast(port), deviceAddress), + "ADXL345"); wpi::SendableRegistry::Add(this, "ADXL345_I2C", port); } diff --git a/wpilibc/src/main/native/cpp/AddressableLED.cpp b/wpilibc/src/main/native/cpp/AddressableLED.cpp index daa5aae47a..d700d18f6d 100644 --- a/wpilibc/src/main/native/cpp/AddressableLED.cpp +++ b/wpilibc/src/main/native/cpp/AddressableLED.cpp @@ -5,10 +5,10 @@ #include "frc/AddressableLED.h" #include -#include #include #include #include +#include #include #include "frc/Errors.h" @@ -31,7 +31,7 @@ AddressableLED::AddressableLED(int port) : m_port{port} { HAL_FreePWMPort(m_pwmHandle); } - HAL_Report(HALUsageReporting::kResourceType_AddressableLEDs, port + 1); + HAL_ReportUsage("IO", port, "AddressableLED"); } void AddressableLED::SetLength(int length) { diff --git a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp index 70d91fcef9..4f5a26c60b 100644 --- a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp @@ -4,7 +4,7 @@ #include "frc/AnalogAccelerometer.h" -#include +#include #include #include #include @@ -53,8 +53,7 @@ void AnalogAccelerometer::InitSendable(wpi::SendableBuilder& builder) { } void AnalogAccelerometer::InitAccelerometer() { - HAL_Report(HALUsageReporting::kResourceType_Accelerometer, - m_analogInput->GetChannel() + 1); + HAL_ReportUsage("IO", m_analogInput->GetChannel(), "Accelerometer"); wpi::SendableRegistry::Add(this, "Accelerometer", m_analogInput->GetChannel()); diff --git a/wpilibc/src/main/native/cpp/AnalogEncoder.cpp b/wpilibc/src/main/native/cpp/AnalogEncoder.cpp index c251ebcf5e..31548e9425 100644 --- a/wpilibc/src/main/native/cpp/AnalogEncoder.cpp +++ b/wpilibc/src/main/native/cpp/AnalogEncoder.cpp @@ -6,6 +6,7 @@ #include +#include #include #include @@ -67,6 +68,8 @@ void AnalogEncoder::Init(double fullRange, double expectedZero) { m_fullRange = fullRange; m_expectedZero = expectedZero; + HAL_ReportUsage("IO", m_analogInput->GetChannel(), "AnalogEncoder"); + wpi::SendableRegistry::Add(this, "Analog Encoder", m_analogInput->GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/AnalogInput.cpp b/wpilibc/src/main/native/cpp/AnalogInput.cpp index 9aa27e7a47..f5cf8a05f6 100644 --- a/wpilibc/src/main/native/cpp/AnalogInput.cpp +++ b/wpilibc/src/main/native/cpp/AnalogInput.cpp @@ -7,9 +7,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -31,7 +31,7 @@ AnalogInput::AnalogInput(int channel) { m_port = HAL_InitializeAnalogInputPort(channel, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); - HAL_Report(HALUsageReporting::kResourceType_AnalogChannel, channel + 1); + HAL_ReportUsage("IO", channel, "AnalogInput"); wpi::SendableRegistry::Add(this, "AnalogInput", channel); } diff --git a/wpilibc/src/main/native/cpp/CAN.cpp b/wpilibc/src/main/native/cpp/CAN.cpp index 2e7b8b747c..a08d16acce 100644 --- a/wpilibc/src/main/native/cpp/CAN.cpp +++ b/wpilibc/src/main/native/cpp/CAN.cpp @@ -9,20 +9,13 @@ #include #include #include -#include +#include #include "frc/Errors.h" using namespace frc; -CAN::CAN(int deviceId) { - int32_t status = 0; - m_handle = - HAL_InitializeCAN(kTeamManufacturer, deviceId, kTeamDeviceType, &status); - FRC_CheckErrorStatus(status, "device id {}", deviceId); - - HAL_Report(HALUsageReporting::kResourceType_CAN, deviceId + 1); -} +CAN::CAN(int deviceId) : CAN{kTeamManufacturer, deviceId, kTeamDeviceType} {} CAN::CAN(int deviceId, int deviceManufacturer, int deviceType) { int32_t status = 0; @@ -32,7 +25,9 @@ CAN::CAN(int deviceId, int deviceManufacturer, int deviceType) { FRC_CheckErrorStatus(status, "device id {} mfg {} type {}", deviceId, deviceManufacturer, deviceType); - HAL_Report(HALUsageReporting::kResourceType_CAN, deviceId + 1); + HAL_ReportUsage( + fmt::format("CAN[{}][{}][{}]", deviceType, deviceManufacturer, deviceId), + ""); } void CAN::WritePacket(const uint8_t* data, int length, int apiId) { diff --git a/wpilibc/src/main/native/cpp/Compressor.cpp b/wpilibc/src/main/native/cpp/Compressor.cpp index bb9a62fbd1..761acf3b3a 100644 --- a/wpilibc/src/main/native/cpp/Compressor.cpp +++ b/wpilibc/src/main/native/cpp/Compressor.cpp @@ -6,7 +6,6 @@ #include -#include #include #include #include @@ -24,7 +23,7 @@ Compressor::Compressor(int module, PneumaticsModuleType moduleType) m_module->EnableCompressorDigital(); - HAL_Report(HALUsageReporting::kResourceType_Compressor, module + 1); + m_module->ReportUsage("Compressor", ""); wpi::SendableRegistry::Add(this, "Compressor", module); } diff --git a/wpilibc/src/main/native/cpp/DataLogManager.cpp b/wpilibc/src/main/native/cpp/DataLogManager.cpp index 92035eb74b..278e824130 100644 --- a/wpilibc/src/main/native/cpp/DataLogManager.cpp +++ b/wpilibc/src/main/native/cpp/DataLogManager.cpp @@ -13,7 +13,7 @@ #include #include -#include +#include #include #include #include @@ -79,8 +79,7 @@ static std::string MakeLogDir(std::string_view dir) { (s.permissions() & fs::perms::others_write) != fs::perms::none) { fs::create_directory("/u/logs", ec); return "/u/logs"; - HAL_Report(HALUsageReporting::kResourceType_DataLogManager, - HALUsageReporting::kDataLogLocation_USB); + HAL_ReportUsage("DataLogManager", "USB"); } if (RobotBase::GetRuntimeType() == kRoboRIO) { FRC_ReportWarning( @@ -88,8 +87,7 @@ static std::string MakeLogDir(std::string_view dir) { "not recommended! Plug in a FAT32 formatted flash drive!"); } fs::create_directory("/home/lvuser/logs", ec); - HAL_Report(HALUsageReporting::kResourceType_DataLogManager, - HALUsageReporting::kDataLogLocation_Onboard); + HAL_ReportUsage("DataLogManager", "Onboard"); return "/home/lvuser/logs"; #else std::string logDir = filesystem::GetOperatingDirectory() + "/logs"; diff --git a/wpilibc/src/main/native/cpp/DigitalInput.cpp b/wpilibc/src/main/native/cpp/DigitalInput.cpp index 19c35eb6ee..fdcfc4393c 100644 --- a/wpilibc/src/main/native/cpp/DigitalInput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalInput.cpp @@ -7,9 +7,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -30,7 +30,7 @@ DigitalInput::DigitalInput(int channel) { m_handle = HAL_InitializeDIOPort(channel, true, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); - HAL_Report(HALUsageReporting::kResourceType_DigitalInput, channel + 1); + HAL_ReportUsage("IO", channel, "DigitalInput"); wpi::SendableRegistry::Add(this, "DigitalInput", channel); } diff --git a/wpilibc/src/main/native/cpp/DigitalOutput.cpp b/wpilibc/src/main/native/cpp/DigitalOutput.cpp index 270c2c1472..4bf0198463 100644 --- a/wpilibc/src/main/native/cpp/DigitalOutput.cpp +++ b/wpilibc/src/main/native/cpp/DigitalOutput.cpp @@ -7,9 +7,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -31,7 +31,7 @@ DigitalOutput::DigitalOutput(int channel) { m_handle = HAL_InitializeDIOPort(channel, false, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); - HAL_Report(HALUsageReporting::kResourceType_DigitalOutput, channel + 1); + HAL_ReportUsage("IO", channel, "DigitalOutput"); wpi::SendableRegistry::Add(this, "DigitalOutput", channel); } diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp index f87d3ebeb7..fb51203039 100644 --- a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp @@ -6,8 +6,6 @@ #include -#include -#include #include #include #include @@ -50,10 +48,9 @@ DoubleSolenoid::DoubleSolenoid(int module, PneumaticsModuleType moduleType, } } - HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_forwardChannel + 1, - m_module->GetModuleNumber() + 1); - HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel + 1, - m_module->GetModuleNumber() + 1); + m_module->ReportUsage( + fmt::format("Solenoid[{},{}]", m_forwardChannel, m_reverseChannel), + "DoubleSolenoid"); wpi::SendableRegistry::Add(this, "DoubleSolenoid", m_module->GetModuleNumber(), m_forwardChannel); diff --git a/wpilibc/src/main/native/cpp/DutyCycle.cpp b/wpilibc/src/main/native/cpp/DutyCycle.cpp index e00320a942..32fac05945 100644 --- a/wpilibc/src/main/native/cpp/DutyCycle.cpp +++ b/wpilibc/src/main/native/cpp/DutyCycle.cpp @@ -8,8 +8,8 @@ #include #include -#include #include +#include #include #include #include @@ -31,7 +31,7 @@ void DutyCycle::InitDutyCycle() { std::string stackTrace = wpi::GetStackTrace(1); m_handle = HAL_InitializeDutyCycle(m_channel, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); - HAL_Report(HALUsageReporting::kResourceType_DutyCycle, m_channel + 1); + HAL_ReportUsage("IO", m_channel, "DutyCycle"); wpi::SendableRegistry::Add(this, "Duty Cycle", m_channel); } diff --git a/wpilibc/src/main/native/cpp/Encoder.cpp b/wpilibc/src/main/native/cpp/Encoder.cpp index a3d4432747..f0fad00e48 100644 --- a/wpilibc/src/main/native/cpp/Encoder.cpp +++ b/wpilibc/src/main/native/cpp/Encoder.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include #include @@ -172,8 +172,19 @@ void Encoder::InitEncoder(int aChannel, int bChannel, bool reverseDirection, static_cast(encodingType), &status); FRC_CheckErrorStatus(status, "InitEncoder"); - HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex() + 1, - encodingType); + const char* type = "Encoder"; + switch (encodingType) { + case k1X: + type = "Encoder:1x"; + break; + case k2X: + type = "Encoder:2x"; + break; + case k4X: + type = "Encoder:4x"; + break; + } + HAL_ReportUsage(fmt::format("IO[{},{}]", aChannel, bChannel), type); // wpi::SendableRegistry::Add(this, "Encoder", m_aSource->GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/I2C.cpp b/wpilibc/src/main/native/cpp/I2C.cpp index 95d5ecf051..976d6e893f 100644 --- a/wpilibc/src/main/native/cpp/I2C.cpp +++ b/wpilibc/src/main/native/cpp/I2C.cpp @@ -6,8 +6,8 @@ #include -#include #include +#include #include "frc/Errors.h" @@ -20,7 +20,8 @@ I2C::I2C(Port port, int deviceAddress) HAL_InitializeI2C(m_port, &status); FRC_CheckErrorStatus(status, "Port {}", static_cast(port)); - HAL_Report(HALUsageReporting::kResourceType_I2C, deviceAddress); + HAL_ReportUsage( + fmt::format("I2C[{}][{}]", static_cast(port), deviceAddress), ""); } I2C::Port I2C::GetPort() const { diff --git a/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp index fc105a2119..567183a4f4 100644 --- a/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp +++ b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp @@ -7,7 +7,6 @@ #include #include -#include #include #include diff --git a/wpilibc/src/main/native/cpp/Joystick.cpp b/wpilibc/src/main/native/cpp/Joystick.cpp index b58a514cbd..7b9ed18127 100644 --- a/wpilibc/src/main/native/cpp/Joystick.cpp +++ b/wpilibc/src/main/native/cpp/Joystick.cpp @@ -6,7 +6,7 @@ #include -#include +#include #include "frc/event/BooleanEvent.h" @@ -19,7 +19,7 @@ Joystick::Joystick(int port) : GenericHID(port) { m_axes[Axis::kTwist] = kDefaultTwistChannel; m_axes[Axis::kThrottle] = kDefaultThrottleChannel; - HAL_Report(HALUsageReporting::kResourceType_Joystick, port + 1); + HAL_ReportUsage("HID", port, "Joystick"); } void Joystick::SetXChannel(int channel) { diff --git a/wpilibc/src/main/native/cpp/Notifier.cpp b/wpilibc/src/main/native/cpp/Notifier.cpp index 9536acc7e1..fb91a06387 100644 --- a/wpilibc/src/main/native/cpp/Notifier.cpp +++ b/wpilibc/src/main/native/cpp/Notifier.cpp @@ -8,7 +8,6 @@ #include #include -#include #include #include diff --git a/wpilibc/src/main/native/cpp/PWM.cpp b/wpilibc/src/main/native/cpp/PWM.cpp index 5c3f8052a8..cba36852dd 100644 --- a/wpilibc/src/main/native/cpp/PWM.cpp +++ b/wpilibc/src/main/native/cpp/PWM.cpp @@ -6,10 +6,10 @@ #include -#include #include #include #include +#include #include #include #include @@ -37,7 +37,7 @@ PWM::PWM(int channel, bool registerSendable) { HAL_SetPWMEliminateDeadband(m_handle, false, &status); FRC_CheckErrorStatus(status, "Channel {}", channel); - HAL_Report(HALUsageReporting::kResourceType_PWM, channel + 1); + HAL_ReportUsage("IO", channel, "PWM"); if (registerSendable) { wpi::SendableRegistry::Add(this, "PWM", channel); } diff --git a/wpilibc/src/main/native/cpp/PneumaticHub.cpp b/wpilibc/src/main/native/cpp/PneumaticHub.cpp index 7169438d9e..004bad29e5 100644 --- a/wpilibc/src/main/native/cpp/PneumaticHub.cpp +++ b/wpilibc/src/main/native/cpp/PneumaticHub.cpp @@ -11,6 +11,7 @@ #include #include +#include #include #include @@ -441,6 +442,10 @@ Compressor PneumaticHub::MakeCompressor() { return Compressor{m_module, PneumaticsModuleType::REVPH}; } +void PneumaticHub::ReportUsage(std::string_view device, std::string_view data) { + HAL_ReportUsage(fmt::format("PH[{}]/{}", m_module, device), data); +} + std::shared_ptr PneumaticHub::GetForModule(int module) { std::string stackTrace = wpi::GetStackTrace(1); std::scoped_lock lock(m_handleLock); diff --git a/wpilibc/src/main/native/cpp/PneumaticsControlModule.cpp b/wpilibc/src/main/native/cpp/PneumaticsControlModule.cpp index e743e5e6f4..cccd1c2896 100644 --- a/wpilibc/src/main/native/cpp/PneumaticsControlModule.cpp +++ b/wpilibc/src/main/native/cpp/PneumaticsControlModule.cpp @@ -7,7 +7,9 @@ #include #include +#include #include +#include #include #include @@ -289,6 +291,11 @@ Compressor PneumaticsControlModule::MakeCompressor() { return Compressor{m_module, PneumaticsModuleType::CTREPCM}; } +void PneumaticsControlModule::ReportUsage(std::string_view device, + std::string_view data) { + HAL_ReportUsage(fmt::format("PCM[{}]/{}", m_module, device), data); +} + std::shared_ptr PneumaticsControlModule::GetForModule( int module) { std::string stackTrace = wpi::GetStackTrace(1); diff --git a/wpilibc/src/main/native/cpp/PowerDistribution.cpp b/wpilibc/src/main/native/cpp/PowerDistribution.cpp index a034723cbb..2b6077f2bc 100644 --- a/wpilibc/src/main/native/cpp/PowerDistribution.cpp +++ b/wpilibc/src/main/native/cpp/PowerDistribution.cpp @@ -7,9 +7,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -41,11 +41,9 @@ PowerDistribution::PowerDistribution() { if (HAL_GetPowerDistributionType(m_handle, &status) == HAL_PowerDistributionType::HAL_PowerDistributionType_kCTRE) { - HAL_Report(HALUsageReporting::kResourceType_PDP, - HALUsageReporting::kPDP_CTRE); + HAL_ReportUsage("PDP", m_module, ""); } else { - HAL_Report(HALUsageReporting::kResourceType_PDP, - HALUsageReporting::kPDP_REV); + HAL_ReportUsage("PDH", m_module, ""); } wpi::SendableRegistry::Add(this, "PowerDistribution", m_module); } @@ -62,11 +60,9 @@ PowerDistribution::PowerDistribution(int module, ModuleType moduleType) { FRC_ReportError(status, "Module {}", module); if (moduleType == ModuleType::kCTRE) { - HAL_Report(HALUsageReporting::kResourceType_PDP, - HALUsageReporting::kPDP_CTRE); + HAL_ReportUsage("PDP_CTRE", m_module, ""); } else { - HAL_Report(HALUsageReporting::kResourceType_PDP, - HALUsageReporting::kPDP_REV); + HAL_ReportUsage("PDH_REV", m_module, ""); } wpi::SendableRegistry::Add(this, "PowerDistribution", m_module); } diff --git a/wpilibc/src/main/native/cpp/Preferences.cpp b/wpilibc/src/main/native/cpp/Preferences.cpp index 9706f90b01..9ba4b68cda 100644 --- a/wpilibc/src/main/native/cpp/Preferences.cpp +++ b/wpilibc/src/main/native/cpp/Preferences.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include @@ -179,5 +179,5 @@ Instance::Instance() { } } }); - HAL_Report(HALUsageReporting::kResourceType_Preferences, 0); + HAL_ReportUsage("Preferences", ""); } diff --git a/wpilibc/src/main/native/cpp/SerialPort.cpp b/wpilibc/src/main/native/cpp/SerialPort.cpp index 8c6fdb380c..36dad45ad8 100644 --- a/wpilibc/src/main/native/cpp/SerialPort.cpp +++ b/wpilibc/src/main/native/cpp/SerialPort.cpp @@ -6,8 +6,8 @@ #include -#include #include +#include #include "frc/Errors.h" @@ -39,8 +39,7 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits, DisableTermination(); - HAL_Report(HALUsageReporting::kResourceType_SerialPort, - static_cast(port) + 1); + HAL_ReportUsage("SerialPort", static_cast(port), ""); } SerialPort::SerialPort(int baudRate, std::string_view portName, Port port, @@ -70,8 +69,7 @@ SerialPort::SerialPort(int baudRate, std::string_view portName, Port port, DisableTermination(); - HAL_Report(HALUsageReporting::kResourceType_SerialPort, - static_cast(port) + 1); + HAL_ReportUsage("SerialPort", static_cast(port), ""); } void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) { diff --git a/wpilibc/src/main/native/cpp/Servo.cpp b/wpilibc/src/main/native/cpp/Servo.cpp index 79f7f549fe..d038346257 100644 --- a/wpilibc/src/main/native/cpp/Servo.cpp +++ b/wpilibc/src/main/native/cpp/Servo.cpp @@ -4,7 +4,7 @@ #include "frc/Servo.h" -#include +#include #include #include @@ -23,7 +23,7 @@ Servo::Servo(int channel) : PWM(channel) { // Assign defaults for period multiplier for the servo PWM control signal SetPeriodMultiplier(kPeriodMultiplier_4X); - HAL_Report(HALUsageReporting::kResourceType_Servo, channel + 1); + HAL_ReportUsage("IO", channel, "Servo"); wpi::SendableRegistry::SetName(this, "Servo", channel); } diff --git a/wpilibc/src/main/native/cpp/SharpIR.cpp b/wpilibc/src/main/native/cpp/SharpIR.cpp index 084ad3b3cf..fca2d9b253 100644 --- a/wpilibc/src/main/native/cpp/SharpIR.cpp +++ b/wpilibc/src/main/native/cpp/SharpIR.cpp @@ -6,6 +6,7 @@ #include +#include #include #include @@ -31,6 +32,7 @@ SharpIR SharpIR::GP2Y0A51SK0F(int channel) { SharpIR::SharpIR(int channel, double a, double b, double minCM, double maxCM) : m_sensor(channel), m_A(a), m_B(b), m_minCM(minCM), m_maxCM(maxCM) { + HAL_ReportUsage("IO", channel, "SharpIR"); wpi::SendableRegistry::Add(this, "SharpIR", channel); m_simDevice = hal::SimDevice("SharpIR", m_sensor.GetChannel()); diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 5bccc8a762..8096955f8a 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -6,7 +6,6 @@ #include -#include #include #include #include @@ -28,8 +27,7 @@ Solenoid::Solenoid(int module, PneumaticsModuleType moduleType, int channel) throw FRC_MakeError(err::ResourceAlreadyAllocated, "Channel {}", m_channel); } - HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_channel + 1, - m_module->GetModuleNumber() + 1); + m_module->ReportUsage(fmt::format("Solenoid[{}]", m_channel), "Solenoid"); wpi::SendableRegistry::Add(this, "Solenoid", m_module->GetModuleNumber(), m_channel); } diff --git a/wpilibc/src/main/native/cpp/Threads.cpp b/wpilibc/src/main/native/cpp/Threads.cpp index 3ecab5569a..db240f6385 100644 --- a/wpilibc/src/main/native/cpp/Threads.cpp +++ b/wpilibc/src/main/native/cpp/Threads.cpp @@ -4,7 +4,6 @@ #include "frc/Threads.h" -#include #include #include "frc/Errors.h" diff --git a/wpilibc/src/main/native/cpp/TimedRobot.cpp b/wpilibc/src/main/native/cpp/TimedRobot.cpp index d2c39d12c5..9ae546e4b5 100644 --- a/wpilibc/src/main/native/cpp/TimedRobot.cpp +++ b/wpilibc/src/main/native/cpp/TimedRobot.cpp @@ -10,8 +10,8 @@ #include #include -#include #include +#include #include "frc/Errors.h" @@ -87,8 +87,7 @@ TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) { FRC_CheckErrorStatus(status, "InitializeNotifier"); HAL_SetNotifierName(m_notifier, "TimedRobot", &status); - HAL_Report(HALUsageReporting::kResourceType_Framework, - HALUsageReporting::kFramework_Timed); + HAL_ReportUsage("Framework", "TimedRobot"); } TimedRobot::~TimedRobot() { diff --git a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp index 16e74421be..f7dbbb8bd4 100644 --- a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp +++ b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include @@ -24,7 +24,7 @@ Tachometer::Tachometer(int channel, EdgeConfiguration configuration) stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "{}", channel); - HAL_Report(HALUsageReporting::kResourceType_Counter, channel + 1); + HAL_ReportUsage("IO", channel, "Tachometer"); wpi::SendableRegistry::Add(this, "Tachometer", channel); } diff --git a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp index e655339301..6ce13b65b0 100644 --- a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp +++ b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include @@ -27,7 +27,7 @@ UpDownCounter::UpDownCounter(int channel, EdgeConfiguration configuration) Reset(); - HAL_Report(HALUsageReporting::kResourceType_Counter, channel + 1); + HAL_ReportUsage("IO", channel, "UpDownCounter"); wpi::SendableRegistry::Add(this, "UpDown Counter", channel); } diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index abd2df149c..6a9a4fbda6 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include @@ -42,8 +42,7 @@ void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation, bool squareInputs) { static bool reported = false; if (!reported) { - HAL_Report(HALUsageReporting::kResourceType_RobotDrive, - HALUsageReporting::kRobotDrive2_DifferentialArcade, 2); + HAL_ReportUsage("RobotDrive", "DifferentialArcade"); reported = true; } @@ -65,8 +64,7 @@ void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation, bool allowTurnInPlace) { static bool reported = false; if (!reported) { - HAL_Report(HALUsageReporting::kResourceType_RobotDrive, - HALUsageReporting::kRobotDrive2_DifferentialCurvature, 2); + HAL_ReportUsage("RobotDrive", "DifferentialCurvature"); reported = true; } @@ -88,8 +86,7 @@ void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed, bool squareInputs) { static bool reported = false; if (!reported) { - HAL_Report(HALUsageReporting::kResourceType_RobotDrive, - HALUsageReporting::kRobotDrive2_DifferentialTank, 2); + HAL_ReportUsage("RobotDrive", "DifferentialTank"); reported = true; } diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index 0cafcb57c8..ded91cb0c4 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -8,7 +8,7 @@ #include #include -#include +#include #include #include @@ -52,8 +52,7 @@ MecanumDrive::MecanumDrive(std::function frontLeftMotor, void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle) { if (!reported) { - HAL_Report(HALUsageReporting::kResourceType_RobotDrive, - HALUsageReporting::kRobotDrive2_MecanumCartesian, 4); + HAL_ReportUsage("RobotDrive", "MecanumCartesian"); reported = true; } @@ -79,8 +78,7 @@ void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed, void MecanumDrive::DrivePolar(double magnitude, Rotation2d angle, double zRotation) { if (!reported) { - HAL_Report(HALUsageReporting::kResourceType_RobotDrive, - HALUsageReporting::kRobotDrive2_MecanumPolar, 4); + HAL_ReportUsage("RobotDrive", "MecanumPolar"); reported = true; } diff --git a/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp index fbd0c6e63e..c5992e7394 100644 --- a/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp +++ b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp @@ -8,8 +8,6 @@ #include #include -#include - #include "frc/motorcontrol/MotorController.h" using namespace frc; diff --git a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp index 0342a01cea..f0bf06c463 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp @@ -7,7 +7,7 @@ #include #include -#include +#include #include #include @@ -26,7 +26,8 @@ NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel) m_dio.SetPWMRate(15625); m_dio.EnablePWM(0.5); - HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel + 1); + HAL_ReportUsage(fmt::format("IO[{},{}]", pwmChannel, dioChannel), + "NidecBrushless"); wpi::SendableRegistry::Add(this, "Nidec Brushless", pwmChannel); } diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp index 8248a94dc8..995f079119 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp @@ -9,7 +9,7 @@ #include #include -#include +#include #include #include #include @@ -77,8 +77,7 @@ bool SmartDashboard::IsPersistent(std::string_view key) { nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) { if (!gReported) { - HAL_Report(HALUsageReporting::kResourceType_SmartDashboard, - HALUsageReporting::kSmartDashboard_Instance); + HAL_ReportUsage("SmartDashboard", ""); gReported = true; } return GetInstance().table->GetEntry(key); @@ -89,8 +88,7 @@ void SmartDashboard::PutData(std::string_view key, wpi::Sendable* data) { throw FRC_MakeError(err::NullParameter, "value"); } if (!gReported) { - HAL_Report(HALUsageReporting::kResourceType_SmartDashboard, - HALUsageReporting::kSmartDashboard_Instance); + HAL_ReportUsage("SmartDashboard", ""); gReported = true; } auto& inst = GetInstance(); diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp index c7113dc330..197aba4adc 100644 --- a/wpilibc/src/main/native/cppcs/RobotBase.cpp +++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp @@ -14,8 +14,8 @@ #include #include -#include #include +#include #include #include #include @@ -45,8 +45,8 @@ int frc::RunHALInitialization() { return -1; } DriverStation::RefreshData(); - HAL_Report(HALUsageReporting::kResourceType_Language, - HALUsageReporting::kLanguage_CPlusPlus, 0, GetWPILibVersion()); + HAL_ReportUsage("Language", "C++"); + HAL_ReportUsage("WPILibVersion", GetWPILibVersion()); if (!frc::Notifier::SetHALThreadPriority(true, 40)) { FRC_ReportWarning("Setting HAL Notifier RT priority to 40 failed\n"); @@ -61,14 +61,8 @@ std::thread::id RobotBase::m_threadId; namespace { class WPILibCameraServerShared : public frc::CameraServerShared { public: - void ReportUsbCamera(int id) override { - HAL_Report(HALUsageReporting::kResourceType_UsbCamera, id); - } - void ReportAxisCamera(int id) override { - HAL_Report(HALUsageReporting::kResourceType_AxisCamera, id); - } - void ReportVideoServer(int id) override { - HAL_Report(HALUsageReporting::kResourceType_PCVideoServer, id); + void ReportUsage(std::string_view resource, std::string_view data) override { + HAL_ReportUsage(resource, data); } void SetCameraServerErrorV(fmt::string_view format, fmt::format_args args) override { @@ -99,53 +93,8 @@ class WPILibMathShared : public wpi::math::MathShared { args); } - void ReportUsage(wpi::math::MathUsageId id, int count) override { - switch (id) { - case wpi::math::MathUsageId::kKinematics_DifferentialDrive: - HAL_Report(HALUsageReporting::kResourceType_Kinematics, - HALUsageReporting::kKinematics_DifferentialDrive); - break; - case wpi::math::MathUsageId::kKinematics_MecanumDrive: - HAL_Report(HALUsageReporting::kResourceType_Kinematics, - HALUsageReporting::kKinematics_MecanumDrive); - break; - case wpi::math::MathUsageId::kKinematics_SwerveDrive: - HAL_Report(HALUsageReporting::kResourceType_Kinematics, - HALUsageReporting::kKinematics_SwerveDrive); - break; - case wpi::math::MathUsageId::kTrajectory_TrapezoidProfile: - HAL_Report(HALUsageReporting::kResourceType_TrapezoidProfile, count); - break; - case wpi::math::MathUsageId::kFilter_Linear: - HAL_Report(HALUsageReporting::kResourceType_LinearFilter, count); - break; - case wpi::math::MathUsageId::kOdometry_DifferentialDrive: - HAL_Report(HALUsageReporting::kResourceType_Odometry, - HALUsageReporting::kOdometry_DifferentialDrive); - break; - case wpi::math::MathUsageId::kOdometry_SwerveDrive: - HAL_Report(HALUsageReporting::kResourceType_Odometry, - HALUsageReporting::kOdometry_SwerveDrive); - break; - case wpi::math::MathUsageId::kOdometry_MecanumDrive: - HAL_Report(HALUsageReporting::kResourceType_Odometry, - HALUsageReporting::kOdometry_MecanumDrive); - break; - case wpi::math::MathUsageId::kController_PIDController2: - HAL_Report(HALUsageReporting::kResourceType_PIDController2, count); - break; - case wpi::math::MathUsageId::kController_ProfiledPIDController: - HAL_Report(HALUsageReporting::kResourceType_ProfiledPIDController, - count); - break; - case wpi::math::MathUsageId::kController_BangBangController: - HAL_Report(HALUsageReporting::kResourceType_BangBangController, count); - break; - case wpi::math::MathUsageId::kTrajectory_PathWeaver: - HAL_Report(HALUsageReporting::kResourceType_PathWeaverTrajectory, - count); - break; - } + void ReportUsage(std::string_view resource, std::string_view data) override { + HAL_ReportUsage(resource, data); } units::second_t GetTimestamp() override { @@ -257,65 +206,13 @@ RobotBase::RobotBase() { } } - connListenerHandle = inst.AddConnectionListener(false, [&](const nt::Event& - event) { - if (event.Is(nt::EventFlags::kConnected)) { - if (event.GetConnectionInfo()->remote_id.starts_with("glass")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_Glass); - m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with( - "SmartDashboard")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_SmartDashboard); - m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with( - "shuffleboard")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_Shuffleboard); - m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with("elastic") || - event.GetConnectionInfo()->remote_id.starts_with("Elastic")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_Elastic); - m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with( - "Dashboard")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_LabVIEW); - m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with( - "AdvantageScope")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_AdvantageScope); - m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with( - "QFRCDashboard")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_QFRCDashboard); - m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with( - "FRC Web Components")) { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_FRCWebComponents); - m_dashboardDetected = true; - } else { - if (!m_dashboardDetected) { - size_t delim = event.GetConnectionInfo()->remote_id.find('@'); - if (delim != std::string::npos) { - HAL_Report( - HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_Unknown, 0, - event.GetConnectionInfo()->remote_id.substr(0, delim).c_str()); - } else { - HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_Unknown, 0, - event.GetConnectionInfo()->remote_id.c_str()); - } + connListenerHandle = + inst.AddConnectionListener(false, [&](const nt::Event& event) { + if (event.Is(nt::EventFlags::kConnected)) { + auto connInfo = event.GetConnectionInfo(); + HAL_ReportUsage(fmt::format("NT/{}", connInfo->remote_id), ""); } - } - } - }); + }); SmartDashboard::init(); diff --git a/wpilibc/src/main/native/include/frc/PneumaticHub.h b/wpilibc/src/main/native/include/frc/PneumaticHub.h index 1b12de634f..37f88be517 100644 --- a/wpilibc/src/main/native/include/frc/PneumaticHub.h +++ b/wpilibc/src/main/native/include/frc/PneumaticHub.h @@ -119,6 +119,8 @@ class PneumaticHub : public PneumaticsBase { int reverseChannel) override; Compressor MakeCompressor() override; + void ReportUsage(std::string_view device, std::string_view data) override; + /** Version and device data received from a REV PH. */ struct Version { /** The firmware major version. */ diff --git a/wpilibc/src/main/native/include/frc/PneumaticsBase.h b/wpilibc/src/main/native/include/frc/PneumaticsBase.h index d8e74d2521..606745e5e2 100644 --- a/wpilibc/src/main/native/include/frc/PneumaticsBase.h +++ b/wpilibc/src/main/native/include/frc/PneumaticsBase.h @@ -5,6 +5,7 @@ #pragma once #include +#include #include #include @@ -255,6 +256,14 @@ class PneumaticsBase { */ virtual Compressor MakeCompressor() = 0; + /** + * Report usage. + * + * @param device device and channel as appropriate + * @param data arbitrary usage data + */ + virtual void ReportUsage(std::string_view device, std::string_view data) = 0; + /** * For internal use to get a module for a specific type. * diff --git a/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h b/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h index 3dd6d3a8ca..c51e9672c9 100644 --- a/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h +++ b/wpilibc/src/main/native/include/frc/PneumaticsControlModule.h @@ -190,6 +190,8 @@ class PneumaticsControlModule : public PneumaticsBase { int reverseChannel) override; Compressor MakeCompressor() override; + void ReportUsage(std::string_view device, std::string_view data) override; + private: class DataStore; friend class DataStore; diff --git a/wpilibc/src/main/native/include/frc/RobotBase.h b/wpilibc/src/main/native/include/frc/RobotBase.h index a0fdcef113..52e62d094d 100644 --- a/wpilibc/src/main/native/include/frc/RobotBase.h +++ b/wpilibc/src/main/native/include/frc/RobotBase.h @@ -276,7 +276,6 @@ class RobotBase { static std::thread::id m_threadId; NT_Listener connListenerHandle; - bool m_dashboardDetected = false; }; } // namespace frc diff --git a/wpilibj/src/generate/hids.json b/wpilibj/src/generate/hids.json index f27806458a..1c58a9597f 100644 --- a/wpilibj/src/generate/hids.json +++ b/wpilibj/src/generate/hids.json @@ -2,7 +2,6 @@ { "ConsoleName": "Xbox", "Manufacturer": "Microsoft", - "SkipReporting": false, "AxisNameSuffix": "Trigger", "buttons": [ { @@ -102,7 +101,6 @@ { "ConsoleName": "PS4", "Manufacturer": "Sony", - "SkipReporting": false, "AxisNameSuffix": "2", "buttons": [ { @@ -217,7 +215,6 @@ { "ConsoleName": "PS5", "Manufacturer": "Sony", - "SkipReporting": true, "AxisNameSuffix": "2", "buttons": [ { @@ -332,7 +329,6 @@ { "ConsoleName": "Stadia", "Manufacturer": "Google", - "SkipReporting": true, "AxisNameSuffix": "Trigger", "buttons": [ { diff --git a/wpilibj/src/generate/hids.schema.json b/wpilibj/src/generate/hids.schema.json index 3b9dca3015..df9e946176 100644 --- a/wpilibj/src/generate/hids.schema.json +++ b/wpilibj/src/generate/hids.schema.json @@ -24,10 +24,6 @@ "description": "The manufacturer of the console", "type": "string" }, - "SkipReporting": { - "description": "Whether or not to skip the usage reporting call", - "type": "boolean" - }, "AxisNameSuffix": { "description": "The suffix of an axis that shouldn't have Axis appended to its name", "type": "string" diff --git a/wpilibj/src/generate/main/java/hid.java.jinja b/wpilibj/src/generate/main/java/hid.java.jinja index 242bf13f75..8fed2a6272 100644 --- a/wpilibj/src/generate/main/java/hid.java.jinja +++ b/wpilibj/src/generate/main/java/hid.java.jinja @@ -8,8 +8,7 @@ {%- endmacro %} package edu.wpi.first.wpilibj; -{{ "// " if SkipReporting }}import edu.wpi.first.hal.FRCNetComm.tResourceType; -{{ "// " if SkipReporting }}import edu.wpi.first.hal.HAL; +import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.wpilibj.event.BooleanEvent; @@ -99,7 +98,7 @@ public class {{ ConsoleName }}Controller extends GenericHID implements Sendable */ public {{ ConsoleName }}Controller(final int port) { super(port); - {{ "// " if SkipReporting }}HAL.report(tResourceType.kResourceType_{{ ConsoleName }}Controller, port + 1); + HAL.reportUsage("HID", port, "{{ ConsoleName }}Controller"); } {% for stick in sticks %} /** diff --git a/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja b/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja index a95145df39..5535a92459 100644 --- a/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja +++ b/wpilibj/src/generate/main/java/pwm_motor_controller.java.jinja @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class {{ name }} extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_{{ ResourceName }}, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "{{ ResourceName }}"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java index 70c1ce1c16..298d3f1419 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS4Controller.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -125,7 +124,7 @@ public class PS4Controller extends GenericHID implements Sendable { */ public PS4Controller(final int port) { super(port); - HAL.report(tResourceType.kResourceType_PS4Controller, port + 1); + HAL.reportUsage("HID", port, "PS4Controller"); } /** diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java index 7cd5bfd5f1..bcb7bf2f2d 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/PS5Controller.java @@ -6,8 +6,7 @@ package edu.wpi.first.wpilibj; -// import edu.wpi.first.hal.FRCNetComm.tResourceType; -// import edu.wpi.first.hal.HAL; +import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.wpilibj.event.BooleanEvent; @@ -125,7 +124,7 @@ public class PS5Controller extends GenericHID implements Sendable { */ public PS5Controller(final int port) { super(port); - // HAL.report(tResourceType.kResourceType_PS5Controller, port + 1); + HAL.reportUsage("HID", port, "PS5Controller"); } /** diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java index 5443e5755b..18e2fe46ae 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/StadiaController.java @@ -6,8 +6,7 @@ package edu.wpi.first.wpilibj; -// import edu.wpi.first.hal.FRCNetComm.tResourceType; -// import edu.wpi.first.hal.HAL; +import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.wpilibj.event.BooleanEvent; @@ -123,7 +122,7 @@ public class StadiaController extends GenericHID implements Sendable { */ public StadiaController(final int port) { super(port); - // HAL.report(tResourceType.kResourceType_StadiaController, port + 1); + HAL.reportUsage("HID", port, "StadiaController"); } /** diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java index 78abae8ed7..a575f2f5c2 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/XboxController.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -117,7 +116,7 @@ public class XboxController extends GenericHID implements Sendable { */ public XboxController(final int port) { super(port); - HAL.report(tResourceType.kResourceType_XboxController, port + 1); + HAL.reportUsage("HID", port, "XboxController"); } /** diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java index 25e11c159b..e0e98bffef 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class DMC60 extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_DigilentDMC60, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "DigilentDMC60"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java index d9638942a3..a75511e6b9 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class Jaguar extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_Jaguar, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "Jaguar"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Koors40.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Koors40.java index df1ef2d754..3ee0960328 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Koors40.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Koors40.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class Koors40 extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_Koors40, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "Koors40"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java index e507efe3de..a601ee95f3 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkFlex.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class PWMSparkFlex extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_RevSparkFlexPWM, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "RevSparkFlexPWM"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java index 88dd49aa93..164554a4a5 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class PWMSparkMax extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_RevSparkMaxPWM, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "RevSparkMaxPWM"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java index 7b5b020464..9f55ee30fe 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class PWMTalonFX extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_TalonFX, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "TalonFX"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java index 21061f4191..a6e1cb111f 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class PWMTalonSRX extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_PWMTalonSRX, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "PWMTalonSRX"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java index 220f0644c0..9fa7264a7d 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class PWMVenom extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_FusionVenom, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "FusionVenom"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java index 570d78a3d3..9dd3f2f23c 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class PWMVictorSPX extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_PWMVictorSPX, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "PWMVictorSPX"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java index 1ee4eebc00..8358ccc95e 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class SD540 extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_MindsensorsSD540, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "MindsensorsSD540"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java index e3b86d1efd..b286aa6ad6 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class Spark extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_RevSPARK, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "RevSPARK"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SparkMini.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SparkMini.java index f4fea85bbc..5c0c71e98e 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SparkMini.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/SparkMini.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class SparkMini extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_RevSPARK, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "RevSPARK"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java index 0e83a17617..63df9d3d6c 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class Talon extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_Talon, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "Talon"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java index 6c6a0c21b0..96e3ac3b37 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class Victor extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_Victor, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "Victor"); } } diff --git a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java index 8f0e2f61bc..7c1a41fb77 100644 --- a/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java +++ b/wpilibj/src/generated/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.PWM; @@ -43,6 +42,6 @@ public class VictorSP extends PWMMotorController { m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); - HAL.report(tResourceType.kResourceType_VictorSP, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "VictorSP"); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java index b898b3ea8e..35d8af9b59 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.hal.SimDouble; @@ -134,7 +132,7 @@ public class ADXL345_I2C implements NTSendable, AutoCloseable { setRange(range); - HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C); + HAL.reportUsage("I2C[" + port.value + "][" + deviceAddress + "]", "ADXL345"); SendableRegistry.add(this, "ADXL345_I2C", port.value); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java index 036d422530..a2c7dd55b0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLED.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.AddressableLEDJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.PWMJNI; @@ -30,7 +29,7 @@ public class AddressableLED implements AutoCloseable { public AddressableLED(int port) { m_pwmHandle = PWMJNI.initializePWMPort(port); m_handle = AddressableLEDJNI.initialize(m_pwmHandle); - HAL.report(tResourceType.kResourceType_AddressableLEDs, port + 1); + HAL.reportUsage("IO", port, "AddressableLED"); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java index 27a1213998..f2198e4a5c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -25,7 +24,7 @@ public class AnalogAccelerometer implements Sendable, AutoCloseable { /** Common initialization. */ private void initAccelerometer() { - HAL.report(tResourceType.kResourceType_Accelerometer, m_analogChannel.getChannel() + 1); + HAL.reportUsage("IO", m_analogChannel.getChannel(), "Accelerometer"); SendableRegistry.add(this, "Accelerometer", m_analogChannel.getChannel()); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java index c455f4c2f6..d76f4d63da 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj; +import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.hal.SimDevice.Direction; import edu.wpi.first.hal.SimDouble; @@ -83,6 +84,8 @@ public class AnalogEncoder implements Sendable, AutoCloseable { m_fullRange = fullRange; m_expectedZero = expectedZero; + HAL.reportUsage("IO", m_analogInput.getChannel(), "AnalogEncoder"); + SendableRegistry.add(this, "Analog Encoder", m_analogInput.getChannel()); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java index 2bca577189..eb5a1c5679 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.util.sendable.Sendable; @@ -28,7 +27,7 @@ public class AnalogGyro implements Sendable, AutoCloseable { /** Initialize the gyro. Calibration is handled by calibrate(). */ private void initGyro() { - HAL.report(tResourceType.kResourceType_Gyro, m_analog.getChannel() + 1); + HAL.reportUsage("AnalogGyro", m_analog.getChannel(), ""); SendableRegistry.add(this, "AnalogGyro", m_analog.getChannel()); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java index fca6d7f388..1590e293eb 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.AnalogJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.util.sendable.Sendable; @@ -40,7 +39,7 @@ public class AnalogInput implements Sendable, AutoCloseable { m_port = AnalogJNI.initializeAnalogInputPort(channel); - HAL.report(tResourceType.kResourceType_AnalogChannel, channel + 1); + HAL.reportUsage("IO", channel, "AnalogInput"); SendableRegistry.add(this, "AnalogInput", channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java index df0be482c2..c1d5eba453 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java @@ -7,7 +7,6 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.CANAPIJNI; import edu.wpi.first.hal.CANAPITypes; import edu.wpi.first.hal.CANData; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import java.io.Closeable; @@ -37,8 +36,7 @@ public class CAN implements Closeable { * @param deviceId The device id */ public CAN(int deviceId) { - m_handle = CANAPIJNI.initializeCAN(kTeamManufacturer, deviceId, kTeamDeviceType); - HAL.report(tResourceType.kResourceType_CAN, deviceId + 1); + this(kTeamManufacturer, deviceId, kTeamDeviceType); } /** @@ -51,7 +49,7 @@ public class CAN implements Closeable { */ public CAN(int deviceId, int deviceManufacturer, int deviceType) { m_handle = CANAPIJNI.initializeCAN(deviceManufacturer, deviceId, deviceType); - HAL.report(tResourceType.kResourceType_CAN, deviceId + 1); + HAL.reportUsage("CAN[" + deviceType + "][" + deviceManufacturer + "][" + deviceId + "]", ""); } /** Closes the CAN communication. */ diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java index b43a3949e6..f68d83fbfd 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.AllocationException; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -44,7 +42,7 @@ public class Compressor implements Sendable, AutoCloseable { m_module.enableCompressorDigital(); - HAL.report(tResourceType.kResourceType_Compressor, module + 1); + m_module.reportUsage("Compressor", ""); SendableRegistry.add(this, "Compressor", module); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java index 53e8b84c2d..c4d1c5be35 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.util.FileLogger; @@ -247,7 +245,7 @@ public final class DataLogManager { if (!new File("/u/logs").mkdir()) { // ignored } - HAL.report(tResourceType.kResourceType_DataLogManager, tInstances.kDataLogLocation_USB); + HAL.reportUsage("DataLogManager", "USB"); return "/u/logs"; } } catch (IOException ex) { @@ -262,7 +260,7 @@ public final class DataLogManager { if (!new File("/home/lvuser/logs").mkdir()) { // ignored } - HAL.report(tResourceType.kResourceType_DataLogManager, tInstances.kDataLogLocation_Onboard); + HAL.reportUsage("DataLogManager", "Onboard"); return "/home/lvuser/logs"; } String logDir = Filesystem.getOperatingDirectory().getAbsolutePath() + "/logs"; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java index 862864308d..ea334567f9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.DIOJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.util.sendable.Sendable; @@ -34,7 +33,7 @@ public class DigitalInput implements AutoCloseable, Sendable { m_handle = DIOJNI.initializeDIOPort(channel, true); - HAL.report(tResourceType.kResourceType_DigitalInput, channel + 1); + HAL.reportUsage("IO", channel, "DigitalInput"); SendableRegistry.add(this, "DigitalInput", channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java index b6aab35ba5..ca8508422a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.DIOJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.util.sendable.Sendable; @@ -36,7 +35,7 @@ public class DigitalOutput implements AutoCloseable, Sendable { m_handle = DIOJNI.initializeDIOPort(channel, false); - HAL.report(tResourceType.kResourceType_DigitalOutput, channel + 1); + HAL.reportUsage("IO", channel, "DigitalOutput"); SendableRegistry.add(this, "DigitalOutput", channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index 73eae77a2f..9b83be9e24 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.AllocationException; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -95,10 +93,8 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { } allocatedSolenoids = true; - HAL.report( - tResourceType.kResourceType_Solenoid, forwardChannel + 1, m_module.getModuleNumber() + 1); - HAL.report( - tResourceType.kResourceType_Solenoid, reverseChannel + 1, m_module.getModuleNumber() + 1); + m_module.reportUsage( + "Solenoid[" + forwardChannel + "," + reverseChannel + "]", "DoubleSolenoid"); SendableRegistry.add(this, "DoubleSolenoid", m_module.getModuleNumber(), forwardChannel); successfulCompletion = true; } finally { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java index a7b8299884..c366152c61 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.DutyCycleJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -35,7 +34,7 @@ public class DutyCycle implements Sendable, AutoCloseable { m_handle = DutyCycleJNI.initialize(channel); m_channel = channel; - HAL.report(tResourceType.kResourceType_DutyCycle, channel + 1); + HAL.reportUsage("IO", channel, "DutyCycle"); SendableRegistry.add(this, "Duty Cycle", channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java index b757fb13ba..59091b6b1b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -7,7 +7,6 @@ package edu.wpi.first.wpilibj; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.hal.EncoderJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.util.sendable.Sendable; @@ -46,8 +45,16 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { int aChannel, int bChannel, boolean reverseDirection, final EncodingType type) { m_encoder = EncoderJNI.initializeEncoder(aChannel, bChannel, reverseDirection, type.value); + String typeStr = + switch (type) { + case k1X -> "Encoder:1x"; + case k2X -> "Encoder:2x"; + case k4X -> "Encoder:4x"; + default -> "Encoder"; + }; + HAL.reportUsage("IO[" + aChannel + "," + bChannel + "]", typeStr); + int fpgaIndex = getFPGAIndex(); - HAL.report(tResourceType.kResourceType_Encoder, fpgaIndex + 1, type.value + 1); SendableRegistry.add(this, "Encoder", fpgaIndex); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java index acb21bc0f0..209e4e7446 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.I2CJNI; import edu.wpi.first.hal.util.BoundaryException; @@ -49,7 +48,7 @@ public class I2C implements AutoCloseable { I2CJNI.i2CInitialize((byte) port.value); - HAL.report(tResourceType.kResourceType_I2C, deviceAddress); + HAL.reportUsage("I2C[" + port.value + "][" + deviceAddress + "]", ""); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java index 08eebeef7d..9e54904310 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java @@ -4,7 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.event.BooleanEvent; import edu.wpi.first.wpilibj.event.EventLoop; @@ -84,7 +83,7 @@ public class Joystick extends GenericHID { m_axes[AxisType.kTwist.value] = kDefaultTwistChannel; m_axes[AxisType.kThrottle.value] = kDefaultThrottleChannel; - HAL.report(tResourceType.kResourceType_Joystick, port + 1); + HAL.reportUsage("HID", port, "Joystick"); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java index 9d1d1bcc6f..d6f0e128f2 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java @@ -4,7 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.PWMConfigDataResult; import edu.wpi.first.hal.PWMJNI; @@ -65,7 +64,7 @@ public class PWM implements Sendable, AutoCloseable { PWMJNI.setPWMEliminateDeadband(m_handle, false); - HAL.report(tResourceType.kResourceType_PWM, channel + 1); + HAL.reportUsage("IO", channel, "PWM"); if (registerSendable) { SendableRegistry.add(this, "PWM", channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java index 127fb94f4f..8dea010d15 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticHub.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj; +import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.PortsJNI; import edu.wpi.first.hal.REVPHFaults; import edu.wpi.first.hal.REVPHJNI; @@ -438,4 +439,9 @@ public class PneumaticHub implements PneumaticsBase { public double getSolenoidsVoltage() { return REVPHJNI.getSolenoidVoltage(m_handle); } + + @Override + public void reportUsage(String device, String data) { + HAL.reportUsage("PH[" + m_dataStore.m_module + "]/" + device, data); + } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java index 2e514192f5..27a3587f33 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java @@ -245,4 +245,12 @@ public interface PneumaticsBase extends AutoCloseable { * @return Compressor object */ Compressor makeCompressor(); + + /** + * Report usage. + * + * @param device device and channel as appropriate + * @param data arbitrary usage data + */ + void reportUsage(String device, String data); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java index c075c46a75..65124e6ea6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsControlModule.java @@ -5,6 +5,7 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.hal.CTREPCMJNI; +import edu.wpi.first.hal.HAL; import java.util.HashMap; import java.util.Map; @@ -344,4 +345,9 @@ public class PneumaticsControlModule implements PneumaticsBase { public double getPressure(int channel) { return 0; } + + @Override + public void reportUsage(String device, String data) { + HAL.reportUsage("PCM[" + m_dataStore.m_module + "]/" + device, data); + } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java index e26c8a2d86..c73fe93583 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.PowerDistributionFaults; import edu.wpi.first.hal.PowerDistributionJNI; @@ -53,9 +51,9 @@ public class PowerDistribution implements Sendable, AutoCloseable { m_module = PowerDistributionJNI.getModuleNumber(m_handle); if (moduleType == ModuleType.kCTRE) { - HAL.report(tResourceType.kResourceType_PDP, tInstances.kPDP_CTRE); + HAL.reportUsage("PDP", m_module, ""); } else { - HAL.report(tResourceType.kResourceType_PDP, tInstances.kPDP_REV); + HAL.reportUsage("PDH", m_module, ""); } SendableRegistry.add(this, "PowerDistribution", m_module); } @@ -71,9 +69,9 @@ public class PowerDistribution implements Sendable, AutoCloseable { m_module = PowerDistributionJNI.getModuleNumber(m_handle); if (PowerDistributionJNI.getType(m_handle) == PowerDistributionJNI.CTRE_TYPE) { - HAL.report(tResourceType.kResourceType_PDP, tInstances.kPDP_CTRE); + HAL.reportUsage("PowerDistribution", m_module, "CTRE"); } else { - HAL.report(tResourceType.kResourceType_PDP, tInstances.kPDP_REV); + HAL.reportUsage("PowerDistribution", m_module, "Rev"); } SendableRegistry.add(this, "PowerDistribution", m_module); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java index b0ab57224e..b1a6a35b0a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.MultiSubscriber; import edu.wpi.first.networktables.NetworkTable; @@ -51,7 +50,7 @@ public final class Preferences { static { setNetworkTableInstance(NetworkTableInstance.getDefault()); - HAL.report(tResourceType.kResourceType_Preferences, 0); + HAL.reportUsage("Preferences", ""); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java index 193c5f7449..9664db456d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -6,13 +6,10 @@ package edu.wpi.first.wpilibj; import edu.wpi.first.cameraserver.CameraServerShared; import edu.wpi.first.cameraserver.CameraServerSharedStore; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.HALUtil; import edu.wpi.first.math.MathShared; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.networktables.MultiSubscriber; import edu.wpi.first.networktables.NetworkTableEvent; import edu.wpi.first.networktables.NetworkTableInstance; @@ -44,19 +41,12 @@ public abstract class RobotBase implements AutoCloseable { private final int m_connListenerHandle; - private boolean m_dashboardDetected; - private static void setupCameraServerShared() { CameraServerShared shared = new CameraServerShared() { @Override - public void reportVideoServer(int id) { - HAL.report(tResourceType.kResourceType_PCVideoServer, id + 1); - } - - @Override - public void reportUsbCamera(int id) { - HAL.report(tResourceType.kResourceType_UsbCamera, id + 1); + public void reportUsage(String resource, String data) { + HAL.reportUsage(resource, data); } @Override @@ -64,11 +54,6 @@ public abstract class RobotBase implements AutoCloseable { DriverStation.reportError(error, true); } - @Override - public void reportAxisCamera(int id) { - HAL.report(tResourceType.kResourceType_AxisCamera, id + 1); - } - @Override public Long getRobotMainThreadId() { return RobotBase.getMainThreadId(); @@ -92,35 +77,8 @@ public abstract class RobotBase implements AutoCloseable { } @Override - public void reportUsage(MathUsageId id, int count) { - switch (id) { - case kKinematics_DifferentialDrive -> HAL.report( - tResourceType.kResourceType_Kinematics, tInstances.kKinematics_DifferentialDrive); - case kKinematics_MecanumDrive -> HAL.report( - tResourceType.kResourceType_Kinematics, tInstances.kKinematics_MecanumDrive); - case kKinematics_SwerveDrive -> HAL.report( - tResourceType.kResourceType_Kinematics, tInstances.kKinematics_SwerveDrive); - case kTrajectory_TrapezoidProfile -> HAL.report( - tResourceType.kResourceType_TrapezoidProfile, count); - case kFilter_Linear -> HAL.report(tResourceType.kResourceType_LinearFilter, count); - case kOdometry_DifferentialDrive -> HAL.report( - tResourceType.kResourceType_Odometry, tInstances.kOdometry_DifferentialDrive); - case kOdometry_SwerveDrive -> HAL.report( - tResourceType.kResourceType_Odometry, tInstances.kOdometry_SwerveDrive); - case kOdometry_MecanumDrive -> HAL.report( - tResourceType.kResourceType_Odometry, tInstances.kOdometry_MecanumDrive); - case kController_PIDController2 -> HAL.report( - tResourceType.kResourceType_PIDController2, count); - case kController_ProfiledPIDController -> HAL.report( - tResourceType.kResourceType_ProfiledPIDController, count); - case kController_BangBangController -> HAL.report( - tResourceType.kResourceType_BangBangController, count); - case kTrajectory_PathWeaver -> HAL.report( - tResourceType.kResourceType_PathWeaverTrajectory, count); - default -> { - // NOP - } - } + public void reportUsage(String resource, String data) { + HAL.reportUsage(resource, data); } @Override @@ -170,57 +128,7 @@ public abstract class RobotBase implements AutoCloseable { false, event -> { if (event.is(NetworkTableEvent.Kind.kConnected)) { - if (event.connInfo.remote_id.startsWith("glass")) { - HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Glass); - m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("SmartDashboard")) { - HAL.report( - tResourceType.kResourceType_Dashboard, tInstances.kDashboard_SmartDashboard); - m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("shuffleboard")) { - HAL.report( - tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Shuffleboard); - m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("elastic") - || event.connInfo.remote_id.startsWith("Elastic")) { - HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Elastic); - m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("Dashboard")) { - HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_LabVIEW); - m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("AdvantageScope")) { - HAL.report( - tResourceType.kResourceType_Dashboard, tInstances.kDashboard_AdvantageScope); - m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("QFRCDashboard")) { - HAL.report( - tResourceType.kResourceType_Dashboard, tInstances.kDashboard_QFRCDashboard); - m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("FRC Web Components")) { - HAL.report( - tResourceType.kResourceType_Dashboard, - tInstances.kDashboard_FRCWebComponents); - m_dashboardDetected = true; - } else { - // Only report unknown if there wasn't another dashboard already reported - // (unknown could also be another device) - if (!m_dashboardDetected) { - int delim = event.connInfo.remote_id.indexOf('@'); - if (delim != -1) { - HAL.report( - tResourceType.kResourceType_Dashboard, - tInstances.kDashboard_Unknown, - 0, - event.connInfo.remote_id.substring(0, delim)); - } else { - HAL.report( - tResourceType.kResourceType_Dashboard, - tInstances.kDashboard_Unknown, - 0, - event.connInfo.remote_id); - } - } - } + HAL.reportUsage("NT/" + event.connInfo.remote_id, ""); } }); } @@ -471,8 +379,8 @@ public abstract class RobotBase implements AutoCloseable { // Force refresh DS data DriverStation.refreshData(); - HAL.report( - tResourceType.kResourceType_Language, tInstances.kLanguage_Java, 0, WPILibVersion.Version); + HAL.reportUsage("Language", "Java"); + HAL.reportUsage("WPILibVersion", WPILibVersion.Version); if (!Notifier.setHALThreadPriority(true, 40)) { DriverStation.reportWarning("Setting HAL Notifier RT priority to 40 failed", false); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java index 92f835d3da..e025cc66e5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java @@ -4,7 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SerialPortJNI; import java.nio.charset.StandardCharsets; @@ -134,7 +133,7 @@ public class SerialPort implements AutoCloseable { disableTermination(); - HAL.report(tResourceType.kResourceType_SerialPort, port.value + 1); + HAL.reportUsage("SerialPort", port.value, ""); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java index 6ba3ed7d57..021f19c06d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java @@ -4,7 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; @@ -37,7 +36,7 @@ public class Servo extends PWM { setBoundsMicroseconds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM); setPeriodMultiplier(PeriodMultiplier.k4X); - HAL.report(tResourceType.kResourceType_Servo, getChannel() + 1); + HAL.reportUsage("IO", getChannel(), "Servo"); SendableRegistry.setName(this, "Servo", getChannel()); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java index 98317a099c..0d48873eb3 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SharpIR.java @@ -4,6 +4,7 @@ package edu.wpi.first.wpilibj; +import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.SimDevice; import edu.wpi.first.hal.SimDevice.Direction; import edu.wpi.first.hal.SimDouble; @@ -89,6 +90,7 @@ public class SharpIR implements Sendable, AutoCloseable { m_minCM = minCM; m_maxCM = maxCM; + HAL.reportUsage("IO", channel, "SharpIR"); SendableRegistry.add(this, "SharpIR", channel); m_simDevice = SimDevice.create("SharpIR", m_sensor.getChannel()); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index 6f78a6130a..9ffb4c6b05 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj; -import edu.wpi.first.hal.FRCNetComm.tResourceType; -import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.util.AllocationException; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -56,7 +54,7 @@ public class Solenoid implements Sendable, AutoCloseable { throw new AllocationException("Solenoid already allocated"); } - HAL.report(tResourceType.kResourceType_Solenoid, channel + 1, m_module.getModuleNumber() + 1); + m_module.reportUsage("Solenoid[" + channel + "]", "Solenoid"); SendableRegistry.add(this, "Solenoid", m_module.getModuleNumber(), channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java index 4525d6aa65..50c853deb4 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java @@ -7,8 +7,6 @@ package edu.wpi.first.wpilibj; import static edu.wpi.first.units.Units.Seconds; import edu.wpi.first.hal.DriverStationJNI; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.hal.NotifierJNI; import edu.wpi.first.units.measure.Time; @@ -92,7 +90,7 @@ public class TimedRobot extends IterativeRobotBase { addPeriodic(this::loopFunc, period); NotifierJNI.setNotifierName(m_notifier, "TimedRobot"); - HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Timed); + HAL.reportUsage("Framework", "TimedRobot"); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java index 0f7e73e304..7ac2b936d1 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj.counter; import edu.wpi.first.hal.CounterJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -33,7 +32,7 @@ public class Tachometer implements Sendable, AutoCloseable { public Tachometer(int channel, EdgeConfiguration configuration) { m_handle = CounterJNI.initializeCounter(channel, configuration.rising); - HAL.report(tResourceType.kResourceType_Counter, channel + 1); + HAL.reportUsage("IO", channel, "Tachometer"); SendableRegistry.add(this, "Tachometer", channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java index c7dee5678f..4fd25d8405 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj.counter; import edu.wpi.first.hal.CounterJNI; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -32,7 +31,7 @@ public class UpDownCounter implements Sendable, AutoCloseable { reset(); - HAL.report(tResourceType.kResourceType_Counter, channel); + HAL.reportUsage("IO", channel, "UpDownCounter"); SendableRegistry.add(this, "UpDown Counter", channel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java index dba563305f..0e0c8211a5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java @@ -6,8 +6,6 @@ package edu.wpi.first.wpilibj.drive; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.math.MathUtil; import edu.wpi.first.util.sendable.Sendable; @@ -157,8 +155,7 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC */ public void arcadeDrive(double xSpeed, double zRotation, boolean squareInputs) { if (!m_reported) { - HAL.report( - tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_DifferentialArcade, 2); + HAL.reportUsage("RobotDrive", "DifferentialArcade"); m_reported = true; } @@ -189,8 +186,7 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC */ public void curvatureDrive(double xSpeed, double zRotation, boolean allowTurnInPlace) { if (!m_reported) { - HAL.report( - tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_DifferentialCurvature, 2); + HAL.reportUsage("RobotDrive", "DifferentialCurvature"); m_reported = true; } @@ -230,8 +226,7 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC */ public void tankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) { if (!m_reported) { - HAL.report( - tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_DifferentialTank, 2); + HAL.reportUsage("RobotDrive", "DifferentialTank"); m_reported = true; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index 9250aba6fa..e0c19e56f2 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -6,8 +6,6 @@ package edu.wpi.first.wpilibj.drive; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; @@ -196,8 +194,7 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea */ public void driveCartesian(double xSpeed, double ySpeed, double zRotation, Rotation2d gyroAngle) { if (!m_reported) { - HAL.report( - tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_MecanumCartesian, 4); + HAL.reportUsage("RobotDrive", "MecanumCartesian"); m_reported = true; } @@ -232,7 +229,7 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea */ public void drivePolar(double magnitude, Rotation2d angle, double zRotation) { if (!m_reported) { - HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_MecanumPolar, 4); + HAL.reportUsage("RobotDrive", "MecanumPolar"); m_reported = true; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java index 0f3d5ad95e..86a777d73a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java @@ -4,7 +4,6 @@ package edu.wpi.first.wpilibj.motorcontrol; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -45,7 +44,7 @@ public class NidecBrushless extends MotorSafety m_pwm = new PWM(pwmChannel); SendableRegistry.addChild(this, m_pwm); - HAL.report(tResourceType.kResourceType_NidecBrushless, pwmChannel + 1); + HAL.reportUsage("IO[" + pwmChannel + "," + dioChannel + "]", "NidecBrushless"); SendableRegistry.add(this, "Nidec Brushless", pwmChannel); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java index 81fbaa6c19..b9584564ea 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java @@ -4,8 +4,6 @@ package edu.wpi.first.wpilibj.smartdashboard; -import edu.wpi.first.hal.FRCNetComm.tInstances; -import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableEntry; @@ -67,7 +65,7 @@ public final class SmartDashboard { @SuppressWarnings("PMD.CompareObjectsWithEquals") public static synchronized void putData(String key, Sendable data) { if (!m_reported) { - HAL.report(tResourceType.kResourceType_SmartDashboard, tInstances.kSmartDashboard_Instance); + HAL.reportUsage("SmartDashboard", ""); m_reported = true; } Sendable sddata = tablesToData.get(key); @@ -121,7 +119,7 @@ public final class SmartDashboard { */ public static NetworkTableEntry getEntry(String key) { if (!m_reported) { - HAL.report(tResourceType.kResourceType_SmartDashboard, tInstances.kSmartDashboard_Instance); + HAL.reportUsage("SmartDashboard", ""); m_reported = true; } return table.getEntry(key); diff --git a/wpimath/src/main/java/edu/wpi/first/math/MathShared.java b/wpimath/src/main/java/edu/wpi/first/math/MathShared.java index ad4e2e81e6..d30690e0a9 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/MathShared.java +++ b/wpimath/src/main/java/edu/wpi/first/math/MathShared.java @@ -17,10 +17,10 @@ public interface MathShared { /** * Report usage. * - * @param id the usage id - * @param count the usage count + * @param resource the resource name + * @param data arbitrary string data */ - void reportUsage(MathUsageId id, int count); + void reportUsage(String resource, String data); /** * Get the current time. diff --git a/wpimath/src/main/java/edu/wpi/first/math/MathSharedStore.java b/wpimath/src/main/java/edu/wpi/first/math/MathSharedStore.java index d490a6e44e..4fcb97c83c 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/MathSharedStore.java +++ b/wpimath/src/main/java/edu/wpi/first/math/MathSharedStore.java @@ -25,7 +25,7 @@ public final class MathSharedStore { public void reportError(String error, StackTraceElement[] stackTrace) {} @Override - public void reportUsage(MathUsageId id, int count) {} + public void reportUsage(String resource, String data) {} @Override public double getTimestamp() { @@ -58,11 +58,11 @@ public final class MathSharedStore { /** * Report usage. * - * @param id the usage id - * @param count the usage count + * @param resource the resource name + * @param data arbitrary string data */ - public static void reportUsage(MathUsageId id, int count) { - getMathShared().reportUsage(id, count); + public static void reportUsage(String resource, String data) { + getMathShared().reportUsage(resource, data); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java b/wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java deleted file mode 100644 index 94c0056743..0000000000 --- a/wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java +++ /dev/null @@ -1,44 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package edu.wpi.first.math; - -/** WPIMath usage reporting IDs. */ -public enum MathUsageId { - /** DifferentialDriveKinematics. */ - kKinematics_DifferentialDrive, - - /** MecanumDriveKinematics. */ - kKinematics_MecanumDrive, - - /** SwerveDriveKinematics. */ - kKinematics_SwerveDrive, - - /** TrapezoidProfile. */ - kTrajectory_TrapezoidProfile, - - /** LinearFilter. */ - kFilter_Linear, - - /** DifferentialDriveOdometry. */ - kOdometry_DifferentialDrive, - - /** SwerveDriveOdometry. */ - kOdometry_SwerveDrive, - - /** MecanumDriveOdometry. */ - kOdometry_MecanumDrive, - - /** PIDController. */ - kController_PIDController2, - - /** ProfiledPIDController. */ - kController_ProfiledPIDController, - - /** BangBangController. */ - kController_BangBangController, - - /** PathWeaver Trajectory. */ - kTrajectory_PathWeaver, -} diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java index 3151e104b1..2bc6a2d4b9 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.controller; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; import edu.wpi.first.util.sendable.SendableRegistry; @@ -45,7 +44,7 @@ public class BangBangController implements Sendable { SendableRegistry.add(this, "BangBangController", instances); - MathSharedStore.reportUsage(MathUsageId.kController_BangBangController, instances); + MathSharedStore.reportUsage("BangBangController", String.valueOf(instances)); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java index dfdf4a2d3c..f2c4e803bb 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/PIDController.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.controller; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.MathUtil; import edu.wpi.first.util.sendable.Sendable; import edu.wpi.first.util.sendable.SendableBuilder; @@ -111,7 +110,7 @@ public class PIDController implements Sendable, AutoCloseable { instances++; SendableRegistry.add(this, "PIDController", instances); - MathSharedStore.reportUsage(MathUsageId.kController_PIDController2, instances); + MathSharedStore.reportUsage("PIDController", String.valueOf(instances)); } @Override diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java index 6c8cd6ea20..f7f8554d61 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.controller; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.trajectory.TrapezoidProfile; import edu.wpi.first.util.sendable.Sendable; @@ -66,7 +65,7 @@ public class ProfiledPIDController implements Sendable { instances++; SendableRegistry.add(this, "ProfiledPIDController", instances); - MathSharedStore.reportUsage(MathUsageId.kController_ProfiledPIDController, instances); + MathSharedStore.reportUsage("ProfiledPIDController", String.valueOf(instances)); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java b/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java index 4a5add4f15..dc738d0a7b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/filter/LinearFilter.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.filter; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.util.DoubleCircularBuffer; import java.util.Arrays; import org.ejml.simple.SimpleMatrix; @@ -73,7 +72,7 @@ public class LinearFilter { m_outputGains = Arrays.copyOf(fbGains, fbGains.length); instances++; - MathSharedStore.reportUsage(MathUsageId.kFilter_Linear, instances); + MathSharedStore.reportUsage("LinearFilter", String.valueOf(instances)); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java index ffa24cd9ba..ddb66ab4c4 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveKinematics.java @@ -7,7 +7,6 @@ package edu.wpi.first.math.kinematics; import static edu.wpi.first.units.Units.Meters; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.geometry.Twist2d; import edu.wpi.first.math.kinematics.proto.DifferentialDriveKinematicsProto; import edu.wpi.first.math.kinematics.struct.DifferentialDriveKinematicsStruct; @@ -47,7 +46,7 @@ public class DifferentialDriveKinematics */ public DifferentialDriveKinematics(double trackWidthMeters) { this.trackWidthMeters = trackWidthMeters; - MathSharedStore.reportUsage(MathUsageId.kKinematics_DifferentialDrive, 1); + MathSharedStore.reportUsage("DifferentialDriveKinematics", ""); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java index 46fb395063..a7c013d19f 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry.java @@ -7,7 +7,6 @@ package edu.wpi.first.math.kinematics; import static edu.wpi.first.units.Units.Meters; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.units.measure.Distance; @@ -41,7 +40,7 @@ public class DifferentialDriveOdometry extends Odometry { MecanumDriveWheelPositions wheelPositions, Pose2d initialPoseMeters) { super(kinematics, gyroAngle, wheelPositions, initialPoseMeters); - MathSharedStore.reportUsage(MathUsageId.kOdometry_MecanumDrive, 1); + MathSharedStore.reportUsage("MecanumDriveOdometry", ""); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java index 00d66c0ab1..a96cf61b0d 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3d.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.kinematics; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; @@ -40,7 +39,7 @@ public class MecanumDriveOdometry3d extends Odometry3d { m_numModules = modulePositions.length; - MathSharedStore.reportUsage(MathUsageId.kOdometry_SwerveDrive, 1); + MathSharedStore.reportUsage("SwerveDriveOdometry", ""); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3d.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3d.java index 35fc6fbc3a..2e21a4fb3a 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3d.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.kinematics; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; @@ -46,7 +45,7 @@ public class SwerveDriveOdometry3d extends Odometry3d { m_numModules = modulePositions.length; - MathSharedStore.reportUsage(MathUsageId.kOdometry_SwerveDrive, 1); + MathSharedStore.reportUsage("SwerveDriveOdometry3d", ""); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java index b42574597d..e258e9d4f3 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryUtil.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.trajectory; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.jni.TrajectoryUtilJNI; @@ -81,7 +80,7 @@ public final class TrajectoryUtil { */ public static Trajectory fromPathweaverJson(Path path) throws IOException { MathSharedStore.reportUsage( - MathUsageId.kTrajectory_PathWeaver, ++pathWeaverTrajectoryInstances); + "Trajectory.PathWeaver", String.valueOf(++pathWeaverTrajectoryInstances)); return createTrajectoryFromElements(TrajectoryUtilJNI.fromPathweaverJson(path.toString())); } diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java index 448c8384cf..4c0f8289c2 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java @@ -5,7 +5,6 @@ package edu.wpi.first.math.trajectory; import edu.wpi.first.math.MathSharedStore; -import edu.wpi.first.math.MathUsageId; import java.util.Objects; /** @@ -66,7 +65,7 @@ public class TrapezoidProfile { public Constraints(double maxVelocity, double maxAcceleration) { this.maxVelocity = maxVelocity; this.maxAcceleration = maxAcceleration; - MathSharedStore.reportUsage(MathUsageId.kTrajectory_TrapezoidProfile, 1); + MathSharedStore.reportUsage("TrapezoidProfile", ""); } } diff --git a/wpimath/src/main/native/cpp/MathShared.cpp b/wpimath/src/main/native/cpp/MathShared.cpp index 5b2d14671f..64c333d5ab 100644 --- a/wpimath/src/main/native/cpp/MathShared.cpp +++ b/wpimath/src/main/native/cpp/MathShared.cpp @@ -20,7 +20,7 @@ class DefaultMathShared : public MathShared { void ReportErrorV(fmt::string_view format, fmt::format_args args) override {} void ReportWarningV(fmt::string_view format, fmt::format_args args) override { } - void ReportUsage(MathUsageId id, int count) override {} + void ReportUsage(std::string_view resource, std::string_view data) override {} units::second_t GetTimestamp() override { return units::second_t{wpi::Now() * 1.0e-6}; } diff --git a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp index d41a1c077f..a22e0994a8 100644 --- a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp +++ b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp @@ -13,6 +13,5 @@ DifferentialDriveOdometry::DifferentialDriveOdometry( units::meter_t rightDistance, const Pose2d& initialPose) : Odometry(m_kinematicsImpl, gyroAngle, {leftDistance, rightDistance}, initialPose) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kOdometry_DifferentialDrive, 1); + wpi::math::MathSharedStore::ReportUsage("DifferentialDriveOdometry", ""); } diff --git a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp index 93fcddbdf0..535dac710a 100644 --- a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp +++ b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp @@ -13,6 +13,5 @@ DifferentialDriveOdometry3d::DifferentialDriveOdometry3d( units::meter_t rightDistance, const Pose3d& initialPose) : Odometry3d(m_kinematicsImpl, gyroAngle, {leftDistance, rightDistance}, initialPose) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kOdometry_DifferentialDrive, 1); + wpi::math::MathSharedStore::ReportUsage("DifferentialDriveOdometry3d", ""); } diff --git a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp index f3431e469e..49ed7e8e2c 100644 --- a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp +++ b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp @@ -13,6 +13,5 @@ MecanumDriveOdometry::MecanumDriveOdometry( const MecanumDriveWheelPositions& wheelPositions, const Pose2d& initialPose) : Odometry(m_kinematicsImpl, gyroAngle, wheelPositions, initialPose), m_kinematicsImpl(kinematics) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kOdometry_MecanumDrive, 1); + wpi::math::MathSharedStore::ReportUsage("MecanumDriveOdometry", ""); } diff --git a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp index bd6954006f..0bbd2cd5dc 100644 --- a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp +++ b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp @@ -13,6 +13,5 @@ MecanumDriveOdometry3d::MecanumDriveOdometry3d( const MecanumDriveWheelPositions& wheelPositions, const Pose3d& initialPose) : Odometry3d(m_kinematicsImpl, gyroAngle, wheelPositions, initialPose), m_kinematicsImpl(kinematics) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kOdometry_MecanumDrive, 1); + wpi::math::MathSharedStore::ReportUsage("MecanumDriveOdometry3d", ""); } diff --git a/wpimath/src/main/native/cpp/trajectory/TrajectoryUtil.cpp b/wpimath/src/main/native/cpp/trajectory/TrajectoryUtil.cpp index 187f8d6cfe..efc9e79678 100644 --- a/wpimath/src/main/native/cpp/trajectory/TrajectoryUtil.cpp +++ b/wpimath/src/main/native/cpp/trajectory/TrajectoryUtil.cpp @@ -37,8 +37,7 @@ Trajectory TrajectoryUtil::FromPathweaverJson(std::string_view path) { wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer()); wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kTrajectory_PathWeaver, - ++pathWeaverTrajectoryInstances); + "Trajectory.PathWeaver", std::to_string(++pathWeaverTrajectoryInstances)); return Trajectory{json.get>()}; } diff --git a/wpimath/src/main/native/include/frc/controller/BangBangController.h b/wpimath/src/main/native/include/frc/controller/BangBangController.h index 897e27318f..25c6fad024 100644 --- a/wpimath/src/main/native/include/frc/controller/BangBangController.h +++ b/wpimath/src/main/native/include/frc/controller/BangBangController.h @@ -45,8 +45,8 @@ class WPILIB_DLLEXPORT BangBangController : m_tolerance(tolerance) { if (!std::is_constant_evaluated()) { ++instances; - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kController_BangBangController, instances); + wpi::math::MathSharedStore::ReportUsage("BangBangController", + std::to_string(instances)); } } diff --git a/wpimath/src/main/native/include/frc/controller/PIDController.h b/wpimath/src/main/native/include/frc/controller/PIDController.h index 7ba9a51541..e5821b537b 100644 --- a/wpimath/src/main/native/include/frc/controller/PIDController.h +++ b/wpimath/src/main/native/include/frc/controller/PIDController.h @@ -74,8 +74,8 @@ class WPILIB_DLLEXPORT PIDController if (!std::is_constant_evaluated()) { ++instances; - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kController_PIDController2, instances); + wpi::math::MathSharedStore::ReportUsage("PIDController", + std::to_string(instances)); wpi::SendableRegistry::Add(this, "PIDController", instances); } } diff --git a/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h b/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h index a717382239..01b6c32e2b 100644 --- a/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h +++ b/wpimath/src/main/native/include/frc/controller/ProfiledPIDController.h @@ -63,8 +63,8 @@ class ProfiledPIDController m_profile{m_constraints} { if (!std::is_constant_evaluated()) { int instances = detail::IncrementAndGetProfiledPIDControllerInstances(); - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kController_ProfiledPIDController, instances); + wpi::math::MathSharedStore::ReportUsage("ProfiledPIDController", + std::to_string(instances)); wpi::SendableRegistry::Add(this, "ProfiledPIDController", instances); } } diff --git a/wpimath/src/main/native/include/frc/filter/LinearFilter.h b/wpimath/src/main/native/include/frc/filter/LinearFilter.h index d51abf2bbf..64b90f5840 100644 --- a/wpimath/src/main/native/include/frc/filter/LinearFilter.h +++ b/wpimath/src/main/native/include/frc/filter/LinearFilter.h @@ -96,8 +96,8 @@ class LinearFilter { if (!std::is_constant_evaluated()) { ++instances; - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kFilter_Linear, instances); + wpi::math::MathSharedStore::ReportUsage("LinearFilter", + std::to_string(instances)); } } diff --git a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h index f605a50456..124a84bdaf 100644 --- a/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h @@ -41,8 +41,8 @@ class WPILIB_DLLEXPORT DifferentialDriveKinematics constexpr explicit DifferentialDriveKinematics(units::meter_t trackWidth) : trackWidth(trackWidth) { if (!std::is_constant_evaluated()) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kKinematics_DifferentialDrive, 1); + wpi::math::MathSharedStore::ReportUsage("DifferentialDriveKinematics", + ""); } } diff --git a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h index 218908fd31..e33eb5ccc9 100644 --- a/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h @@ -66,8 +66,7 @@ class WPILIB_DLLEXPORT MecanumDriveKinematics SetInverseKinematics(frontLeftWheel, frontRightWheel, rearLeftWheel, rearRightWheel); m_forwardKinematics = m_inverseKinematics.householderQr(); - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kKinematics_MecanumDrive, 1); + wpi::math::MathSharedStore::ReportUsage("MecanumDriveKinematics", ""); } MecanumDriveKinematics(const MecanumDriveKinematics&) = default; diff --git a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h index 276f9a8818..8c56467893 100644 --- a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h @@ -78,8 +78,7 @@ class SwerveDriveKinematics m_forwardKinematics = m_inverseKinematics.householderQr(); - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kKinematics_SwerveDrive, 1); + wpi::math::MathSharedStore::ReportUsage("SwerveDriveKinematics", ""); } explicit SwerveDriveKinematics( @@ -95,8 +94,7 @@ class SwerveDriveKinematics m_forwardKinematics = m_inverseKinematics.householderQr(); - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kKinematics_SwerveDrive, 1); + wpi::math::MathSharedStore::ReportUsage("Kinematics_SwerveDrive", ""); } SwerveDriveKinematics(const SwerveDriveKinematics&) = default; diff --git a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h index 91eb87d8a3..f7e6c34a7b 100644 --- a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h +++ b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h @@ -48,8 +48,7 @@ class SwerveDriveOdometry : SwerveDriveOdometry::Odometry(m_kinematicsImpl, gyroAngle, modulePositions, initialPose), m_kinematicsImpl(kinematics) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kOdometry_SwerveDrive, 1); + wpi::math::MathSharedStore::ReportUsage("SwerveDriveOdometry", ""); } private: diff --git a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry3d.h b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry3d.h index 0215a2c5dc..062118582c 100644 --- a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry3d.h +++ b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveOdometry3d.h @@ -53,8 +53,7 @@ class SwerveDriveOdometry3d : SwerveDriveOdometry3d::Odometry3d(m_kinematicsImpl, gyroAngle, modulePositions, initialPose), m_kinematicsImpl(kinematics) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kOdometry_SwerveDrive, 1); + wpi::math::MathSharedStore::ReportUsage("SwerveDriveOdometry3d", ""); } #if defined(__GNUC__) && !defined(__clang__) #pragma GCC diagnostic pop diff --git a/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h b/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h index 9dd82f4eee..1dad991c30 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h +++ b/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h @@ -69,8 +69,7 @@ class TrapezoidProfile { */ constexpr Constraints() { if (!std::is_constant_evaluated()) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kTrajectory_TrapezoidProfile, 1); + wpi::math::MathSharedStore::ReportUsage("TrapezoidProfile", ""); } } @@ -84,8 +83,7 @@ class TrapezoidProfile { Acceleration_t maxAcceleration) : maxVelocity{maxVelocity}, maxAcceleration{maxAcceleration} { if (!std::is_constant_evaluated()) { - wpi::math::MathSharedStore::ReportUsage( - wpi::math::MathUsageId::kTrajectory_TrapezoidProfile, 1); + wpi::math::MathSharedStore::ReportUsage("TrapezoidProfile", ""); } } }; diff --git a/wpimath/src/main/native/include/wpimath/MathShared.h b/wpimath/src/main/native/include/wpimath/MathShared.h index 4394b707a7..389e548927 100644 --- a/wpimath/src/main/native/include/wpimath/MathShared.h +++ b/wpimath/src/main/native/include/wpimath/MathShared.h @@ -13,28 +13,14 @@ namespace wpi::math { -enum class MathUsageId { - kKinematics_DifferentialDrive, - kKinematics_MecanumDrive, - kKinematics_SwerveDrive, - kTrajectory_TrapezoidProfile, - kFilter_Linear, - kOdometry_DifferentialDrive, - kOdometry_SwerveDrive, - kOdometry_MecanumDrive, - kController_PIDController2, - kController_ProfiledPIDController, - kController_BangBangController, - kTrajectory_PathWeaver, -}; - class WPILIB_DLLEXPORT MathShared { public: virtual ~MathShared() = default; virtual void ReportErrorV(fmt::string_view format, fmt::format_args args) = 0; virtual void ReportWarningV(fmt::string_view format, fmt::format_args args) = 0; - virtual void ReportUsage(MathUsageId id, int count) = 0; + virtual void ReportUsage(std::string_view resource, + std::string_view data) = 0; virtual units::second_t GetTimestamp() = 0; template @@ -72,8 +58,8 @@ class WPILIB_DLLEXPORT MathSharedStore { ReportWarningV(format, fmt::make_format_args(args...)); } - static void ReportUsage(MathUsageId id, int count) { - GetMathShared().ReportUsage(id, count); + static void ReportUsage(std::string_view resource, std::string_view data) { + GetMathShared().ReportUsage(resource, data); } static units::second_t GetTimestamp() {