mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[hal] Change usage reporting to string-based (#7763)
This commit is contained in:
3
.github/actions/pregen/action.yml
vendored
3
.github/actions/pregen/action.yml
vendored
@@ -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
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
#include <string_view>
|
||||
#include <thread>
|
||||
#include <utility>
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -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", "");
|
||||
}
|
||||
""");
|
||||
|
||||
|
||||
@@ -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();
|
||||
|
||||
@@ -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 = [
|
||||
|
||||
@@ -19,7 +19,6 @@ target_include_directories(
|
||||
hal
|
||||
PUBLIC
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/generated/main/native/include>
|
||||
$<INSTALL_INTERFACE:${include_dest}/hal>
|
||||
)
|
||||
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}
|
||||
)
|
||||
|
||||
70
hal/doc/usage.adoc
Normal file
70
hal/doc/usage.adoc
Normal file
@@ -0,0 +1,70 @@
|
||||
= WPILib Usage Reporting Guidelines, Version 1.0
|
||||
WPILib Developers <wpilib@wpi.edu>
|
||||
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
|
||||
|===
|
||||
@@ -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()
|
||||
@@ -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 <b>FRC_NetworkCommunication</b><br>.
|
||||
*/
|
||||
@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() {}
|
||||
}
|
||||
@@ -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 <stdint.h>
|
||||
|
||||
#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
|
||||
@@ -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
|
||||
@@ -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
|
||||
@@ -1,55 +0,0 @@
|
||||
|
||||
#ifndef __UsageReporting_h__
|
||||
#define __UsageReporting_h__
|
||||
|
||||
#ifdef _WIN32
|
||||
#include <stdint.h>
|
||||
#define EXPORT_FUNC __declspec(dllexport) __cdecl
|
||||
#elif defined(__vxworks)
|
||||
#include <vxWorks.h>
|
||||
#define EXPORT_FUNC
|
||||
#else
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#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__
|
||||
@@ -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 <b>FRC_NetworkCommunication</b><br>.
|
||||
*/
|
||||
@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() {}
|
||||
}
|
||||
@@ -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 <stdint.h>
|
||||
|
||||
#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
|
||||
@@ -1,260 +0,0 @@
|
||||
|
||||
#ifndef __UsageReporting_h__
|
||||
#define __UsageReporting_h__
|
||||
|
||||
#ifdef _WIN32
|
||||
#include <stdint.h>
|
||||
#define EXPORT_FUNC __declspec(dllexport) __cdecl
|
||||
#elif defined(__vxworks)
|
||||
#include <vxWorks.h>
|
||||
#define EXPORT_FUNC
|
||||
#else
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#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__
|
||||
@@ -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.
|
||||
*
|
||||
* <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
|
||||
* char*)</code>
|
||||
*
|
||||
* @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.
|
||||
*
|
||||
* <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
|
||||
* char*)</code>
|
||||
*
|
||||
* @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.
|
||||
*
|
||||
* <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
|
||||
* char*)</code>
|
||||
*
|
||||
* @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.
|
||||
*
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
* <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
|
||||
* char*)</code>
|
||||
*
|
||||
* @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.
|
||||
*
|
||||
* <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
|
||||
* char*)</code>
|
||||
*
|
||||
* @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.
|
||||
*
|
||||
* <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
|
||||
* char*)</code>
|
||||
*
|
||||
* @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() {}
|
||||
|
||||
25
hal/src/main/java/edu/wpi/first/hal/UsageReportingJNI.java
Normal file
25
hal/src/main/java/edu/wpi/first/hal/UsageReportingJNI.java
Normal file
@@ -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() {}
|
||||
}
|
||||
12
hal/src/main/native/cpp/UsageReporting.cpp
Normal file
12
hal/src/main/native/cpp/UsageReporting.cpp
Normal file
@@ -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 <fmt/format.h>
|
||||
|
||||
int32_t HAL_ReportUsage(std::string_view resource, int instanceNumber,
|
||||
std::string_view data) {
|
||||
return HAL_ReportUsage(fmt::format("{}[{}]", resource, instanceNumber), data);
|
||||
}
|
||||
@@ -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
|
||||
|
||||
35
hal/src/main/native/cpp/jni/UsageReportingJNI.cpp
Normal file
35
hal/src/main/native/cpp/jni/UsageReportingJNI.cpp
Normal file
@@ -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 <jni.h>
|
||||
|
||||
#include <cassert>
|
||||
|
||||
#include <wpi/jni_util.h>
|
||||
#include <wpi/string.h>
|
||||
|
||||
#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"
|
||||
@@ -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"
|
||||
|
||||
66
hal/src/main/native/include/hal/UsageReporting.h
Normal file
66
hal/src/main/native/include/hal/UsageReporting.h
Normal file
@@ -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 <stdint.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
#include <string_view>
|
||||
#endif
|
||||
|
||||
#include <wpi/string.h>
|
||||
|
||||
#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
|
||||
@@ -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
|
||||
}
|
||||
|
||||
|
||||
@@ -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"
|
||||
|
||||
@@ -43,4 +43,5 @@ extern void InitializePWM();
|
||||
extern void InitializeSerialPort();
|
||||
extern void InitializeSmartIo();
|
||||
extern void InitializeThreads();
|
||||
extern void InitializeUsageReporting();
|
||||
} // namespace hal::init
|
||||
|
||||
51
hal/src/main/native/systemcore/UsageReporting.cpp
Normal file
51
hal/src/main/native/systemcore/UsageReporting.cpp
Normal file
@@ -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 <stdint.h>
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <networktables/NetworkTableInstance.h>
|
||||
#include <networktables/StringTopic.h>
|
||||
#include <wpi/StringMap.h>
|
||||
#include <wpi/string.h>
|
||||
|
||||
#include "SystemServerInternal.h"
|
||||
|
||||
namespace {
|
||||
struct SystemServerUsageReporting {
|
||||
nt::NetworkTableInstance ntInst;
|
||||
wpi::StringMap<nt::StringPublisher> 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
|
||||
@@ -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");
|
||||
}
|
||||
|
||||
|
||||
@@ -13,8 +13,8 @@
|
||||
#include <frc/RobotBase.h>
|
||||
#include <frc/RobotState.h>
|
||||
#include <frc/TimedRobot.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <networktables/IntegerArrayTopic.h>
|
||||
#include <networktables/StringArrayTopic.h>
|
||||
#include <wpi/DenseMap.h>
|
||||
@@ -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");
|
||||
}
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
{%- endmacro %}
|
||||
#include "frc/{{ ConsoleName }}Controller.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#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 {
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/{{ name }}.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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 }}");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/PS4Controller.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#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 {
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/PS5Controller.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#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 {
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/StadiaController.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#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 {
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/XboxController.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
#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 {
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/DMC60.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/Jaguar.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/Koors40.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/PWMSparkFlex.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/PWMSparkMax.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/PWMTalonFX.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/PWMTalonSRX.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/PWMVenom.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/PWMVictorSPX.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/SD540.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/Spark.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/SparkMini.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/Talon.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/Victor.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include "frc/motorcontrol/VictorSP.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
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");
|
||||
}
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include "frc/ADXL345_I2C.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <networktables/DoubleTopic.h>
|
||||
#include <networktables/NTSendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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<int>(port), deviceAddress),
|
||||
"ADXL345");
|
||||
|
||||
wpi::SendableRegistry::Add(this, "ADXL345_I2C", port);
|
||||
}
|
||||
|
||||
@@ -5,10 +5,10 @@
|
||||
#include "frc/AddressableLED.h"
|
||||
|
||||
#include <hal/AddressableLED.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/PWM.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
|
||||
#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) {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include "frc/AnalogAccelerometer.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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());
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
|
||||
#include <utility>
|
||||
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
@@ -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());
|
||||
}
|
||||
|
||||
@@ -7,9 +7,9 @@
|
||||
#include <string>
|
||||
|
||||
#include <hal/AnalogInput.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -9,20 +9,13 @@
|
||||
#include <hal/CAN.h>
|
||||
#include <hal/CANAPI.h>
|
||||
#include <hal/Errors.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
#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) {
|
||||
|
||||
@@ -6,7 +6,6 @@
|
||||
|
||||
#include <frc/PneumaticHub.h>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -13,7 +13,7 @@
|
||||
#include <vector>
|
||||
|
||||
#include <fmt/chrono.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <networktables/NetworkTableInstance.h>
|
||||
#include <wpi/DataLog.h>
|
||||
#include <wpi/DataLogBackgroundWriter.h>
|
||||
@@ -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";
|
||||
|
||||
@@ -7,9 +7,9 @@
|
||||
#include <string>
|
||||
|
||||
#include <hal/DIO.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@
|
||||
#include <string>
|
||||
|
||||
#include <hal/DIO.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -6,8 +6,6 @@
|
||||
|
||||
#include <utility>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
@@ -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);
|
||||
|
||||
@@ -8,8 +8,8 @@
|
||||
#include <utility>
|
||||
|
||||
#include <hal/DutyCycle.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
#include <utility>
|
||||
|
||||
#include <hal/Encoder.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -172,8 +172,19 @@ void Encoder::InitEncoder(int aChannel, int bChannel, bool reverseDirection,
|
||||
static_cast<HAL_EncoderEncodingType>(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());
|
||||
}
|
||||
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/I2C.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
#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<int>(port));
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_I2C, deviceAddress);
|
||||
HAL_ReportUsage(
|
||||
fmt::format("I2C[{}][{}]", static_cast<int>(port), deviceAddress), "");
|
||||
}
|
||||
|
||||
I2C::Port I2C::GetPort() const {
|
||||
|
||||
@@ -7,7 +7,6 @@
|
||||
#include <frc/DriverStation.h>
|
||||
|
||||
#include <hal/DriverStation.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <networktables/NetworkTableInstance.h>
|
||||
#include <wpi/print.h>
|
||||
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
#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) {
|
||||
|
||||
@@ -8,7 +8,6 @@
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <hal/DriverStation.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/Notifier.h>
|
||||
#include <hal/Threads.h>
|
||||
|
||||
|
||||
@@ -6,10 +6,10 @@
|
||||
|
||||
#include <utility>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/PWM.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -11,6 +11,7 @@
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <hal/REVPH.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
|
||||
@@ -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<PneumaticsBase> PneumaticHub::GetForModule(int module) {
|
||||
std::string stackTrace = wpi::GetStackTrace(1);
|
||||
std::scoped_lock lock(m_handleLock);
|
||||
|
||||
@@ -7,7 +7,9 @@
|
||||
#include <memory>
|
||||
#include <string>
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <hal/CTREPCM.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
|
||||
@@ -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<PneumaticsBase> PneumaticsControlModule::GetForModule(
|
||||
int module) {
|
||||
std::string stackTrace = wpi::GetStackTrace(1);
|
||||
|
||||
@@ -7,9 +7,9 @@
|
||||
#include <vector>
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/Ports.h>
|
||||
#include <hal/PowerDistribution.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include <vector>
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <networktables/MultiSubscriber.h>
|
||||
#include <networktables/NetworkTable.h>
|
||||
#include <networktables/NetworkTableInstance.h>
|
||||
@@ -179,5 +179,5 @@ Instance::Instance() {
|
||||
}
|
||||
}
|
||||
});
|
||||
HAL_Report(HALUsageReporting::kResourceType_Preferences, 0);
|
||||
HAL_ReportUsage("Preferences", "");
|
||||
}
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <string>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/SerialPort.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
#include "frc/Errors.h"
|
||||
|
||||
@@ -39,8 +39,7 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits,
|
||||
|
||||
DisableTermination();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_SerialPort,
|
||||
static_cast<uint8_t>(port) + 1);
|
||||
HAL_ReportUsage("SerialPort", static_cast<int>(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<uint8_t>(port) + 1);
|
||||
HAL_ReportUsage("SerialPort", static_cast<int>(port), "");
|
||||
}
|
||||
|
||||
void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include "frc/Servo.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
@@ -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());
|
||||
|
||||
@@ -6,7 +6,6 @@
|
||||
|
||||
#include <utility>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/NullDeleter.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -4,7 +4,6 @@
|
||||
|
||||
#include "frc/Threads.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/Threads.h>
|
||||
|
||||
#include "frc/Errors.h"
|
||||
|
||||
@@ -10,8 +10,8 @@
|
||||
#include <utility>
|
||||
|
||||
#include <hal/DriverStation.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/Notifier.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
|
||||
#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() {
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
#include <string>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
#include <string>
|
||||
|
||||
#include <hal/Counter.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/StackTrace.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
@@ -52,8 +52,7 @@ MecanumDrive::MecanumDrive(std::function<void(double)> 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;
|
||||
}
|
||||
|
||||
|
||||
@@ -8,8 +8,6 @@
|
||||
#include <cmath>
|
||||
#include <cstddef>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
|
||||
#include "frc/motorcontrol/MotorController.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
#include <string>
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include <utility>
|
||||
#include <vector>
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <networktables/NetworkTable.h>
|
||||
#include <networktables/NetworkTableInstance.h>
|
||||
#include <wpi/StringMap.h>
|
||||
@@ -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();
|
||||
|
||||
@@ -14,8 +14,8 @@
|
||||
#include <utility>
|
||||
|
||||
#include <cameraserver/CameraServerShared.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <hal/HALBase.h>
|
||||
#include <hal/UsageReporting.h>
|
||||
#include <networktables/NetworkTable.h>
|
||||
#include <networktables/NetworkTableInstance.h>
|
||||
#include <wpi/print.h>
|
||||
@@ -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,63 +206,11 @@ RobotBase::RobotBase() {
|
||||
}
|
||||
}
|
||||
|
||||
connListenerHandle = inst.AddConnectionListener(false, [&](const nt::Event&
|
||||
event) {
|
||||
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());
|
||||
}
|
||||
}
|
||||
}
|
||||
auto connInfo = event.GetConnectionInfo();
|
||||
HAL_ReportUsage(fmt::format("NT/{}", connInfo->remote_id), "");
|
||||
}
|
||||
});
|
||||
|
||||
|
||||
@@ -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. */
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
#include <string_view>
|
||||
|
||||
#include <units/current.h>
|
||||
#include <units/pressure.h>
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -276,7 +276,6 @@ class RobotBase {
|
||||
|
||||
static std::thread::id m_threadId;
|
||||
NT_Listener connListenerHandle;
|
||||
bool m_dashboardDetected = false;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
|
||||
@@ -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": [
|
||||
{
|
||||
|
||||
@@ -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"
|
||||
|
||||
@@ -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 %}
|
||||
/**
|
||||
|
||||
@@ -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 }}");
|
||||
}
|
||||
}
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user