Refactored wpilibj HAL JNI to simplify generating it from HAL headers (#109)

wpilibj FRCNetworkCommunication.java is now generated from HAL headers and was renamed to FRCNetComm.java
This commit is contained in:
Tyler Veness
2016-07-10 16:24:57 -07:00
committed by Peter Johnson
parent aafca4ed7f
commit e44a6e227a
61 changed files with 932 additions and 770 deletions

178
gen/wpilibj_frcnetcomm.py Executable file
View File

@@ -0,0 +1,178 @@
#!/usr/bin/env python3
# This script generates the network communication interface for wpilibj.
#
# This script takes no arguments and should be invoked from either the gen
# directory or the root directory of the project.
from datetime import date
import os
import re
import subprocess
# Check that the current directory is part of a Git repository
def inGitRepo(directory):
ret = subprocess.run(["git", "rev-parse"], stderr = subprocess.DEVNULL)
return ret.returncode == 0
def main():
if not inGitRepo("."):
print("Error: not invoked within a Git repository", file = sys.stderr)
sys.exit(1)
# Handle running in either the root or gen directories
configPath = "."
if os.getcwd().rpartition(os.sep)[2] == "gen":
configPath = ".."
outputName = configPath + \
"/wpilibj/src/athena/java/edu/wpi/first/wpilibj/hal/FRCNetComm.java"
# Set initial copyright year and get current year
year = "2016"
currentYear = str(date.today().year)
# Start writing output file
with open(outputName + ".tmp", "w") as temp:
# Write first line of comment
temp.write("/*")
for i in range(0, 76):
temp.write("-")
temp.write("*/\n")
# Write second line of comment
temp.write("/* Copyright (c) FIRST ")
if year != currentYear:
temp.write(year)
temp.write("-")
temp.write(currentYear)
temp.write(". All Rights Reserved.")
for i in range(0, 24):
temp.write(" ")
if year == currentYear:
for i in range(0, 5):
temp.write(" ")
temp.write("*/\n")
# Write rest of lines of comment
temp.write("""\
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*""")
for i in range(0, 76):
temp.write("-")
temp.write("*/\n")
# Write preamble
temp.write("""
package edu.wpi.first.wpilibj.hal;
import edu.wpi.first.wpilibj.hal.JNIWrapper;
/**
* JNI wrapper for library <b>FRC_NetworkCommunication</b><br>.
*/
@SuppressWarnings(\"MethodName\")
public class FRCNetComm extends JNIWrapper {
""")
# Read enums from C++ source files
firstEnum = True
for fileName in ["LoadOut.h", "UsageReporting.h"]:
with open(configPath + "/hal/include/FRC_NetworkCommunication/" + \
fileName, "r") as cppSource:
while True:
# Read until an enum is encountered
line = ""
pos = -1
while line.find("enum") == -1:
line = cppSource.readline()
if line == "":
break
if line == "":
break
# If "{" is on next line, read next line
if line.find("{") == -1:
line = cppSource.readline()
# Write enum to output file as interface
values = []
line = cppSource.readline()
while line.find("}") == -1:
if line == "\n":
values.append("")
else:
if line[0] != "#":
line = line.strip()
if line[len(line) - 1] == ",":
values.append(line[0:len(line) - 1])
else:
values.append(line)
line = cppSource.readline()
# Extract enum name
nameStart = 0
for i, c in enumerate(line):
if c != " " and c != "}":
nameStart = i
break
enumName = line[nameStart:len(line) - 2]
# Write comment for interface name
# Only add newline if not the first enum
if firstEnum == True:
firstEnum = False
else:
temp.write("\n")
temp.write(" /**\n"
" * ")
# Splits camelcase string into words
enumCamel = re.findall(r'[A-Z](?:[a-z]+|[A-Z]*(?=[A-Z]|$))',
enumName)
temp.write(enumCamel[0] + " ")
for i in range(1, len(enumCamel)):
temp.write(enumCamel[i][0].lower() + \
enumCamel[i][1:len(enumCamel[i])] + " ")
temp.write("from " + fileName + "\n"
" */\n"
" @SuppressWarnings(\"TypeName\")\n"
" public interface " + enumName + " {\n")
# Write enum values
count = 0
for value in values:
# Pass through empty lines
if value == "":
temp.write("\n")
continue
if value.find("=") == -1:
value = value + " = " + str(count)
count += 1
# Add scoping for values from a different enum
if enumName != "tModuleType" and \
value.find("kModuleType") != -1:
value = value.replace("kModuleType",
"tModuleType.kModuleType")
temp.write(" int " + value[0:len(value)] + ";\n")
# Write end of enum
temp.write(" }\n")
# Write closing brace for file
temp.write("}\n")
# Replace old output file
try:
os.remove(outputName)
except OSError:
pass
os.rename(outputName + ".tmp", outputName)
if __name__ == "__main__":
main()

View File

@@ -120,8 +120,8 @@ int HAL_SendError(int isError, int32_t errorCode, int isLVCode,
const char* details, const char* location,
const char* callStack, int printMsg);
int HAL_GetControlWord(HAL_ControlWord* data);
int HAL_GetAllianceStation(enum HAL_AllianceStationID* allianceStation);
int HAL_GetControlWord(HAL_ControlWord* controlWord);
HAL_AllianceStationID HAL_GetAllianceStation(int32_t* status);
int HAL_GetJoystickAxes(uint8_t joystickNum, HAL_JoystickAxes* axes);
int HAL_GetJoystickPOVs(uint8_t joystickNum, HAL_JoystickPOVs* povs);
int HAL_GetJoystickButtons(uint8_t joystickNum, HAL_JoystickButtons* buttons);
@@ -133,7 +133,7 @@ char* HAL_GetJoystickName(uint8_t joystickNum);
int HAL_GetJoystickAxisType(uint8_t joystickNum, uint8_t axis);
int HAL_SetJoystickOutputs(uint8_t joystickNum, uint32_t outputs,
uint16_t leftRumble, uint16_t rightRumble);
int HAL_GetMatchTime(float* matchTime);
float HAL_GetMatchTime(int32_t* status);
void HAL_SetNewDataSem(MULTIWAIT_ID sem);
@@ -141,11 +141,11 @@ bool HAL_GetSystemActive(int32_t* status);
bool HAL_GetBrownedOut(int32_t* status);
int HAL_Initialize(int mode = 0);
void HAL_NetworkCommunicationObserveUserProgramStarting();
void HAL_NetworkCommunicationObserveUserProgramDisabled();
void HAL_NetworkCommunicationObserveUserProgramAutonomous();
void HAL_NetworkCommunicationObserveUserProgramTeleop();
void HAL_NetworkCommunicationObserveUserProgramTest();
void HAL_ObserveUserProgramStarting();
void HAL_ObserveUserProgramDisabled();
void HAL_ObserveUserProgramAutonomous();
void HAL_ObserveUserProgramTeleop();
void HAL_ObserveUserProgramTest();
uint32_t HAL_Report(uint8_t resource, uint8_t instanceNumber,
uint8_t context = 0, const char* feature = nullptr);

View File

@@ -18,17 +18,21 @@ struct HAL_JoystickAxesInt {
extern "C" {
int HAL_GetControlWord(HAL_ControlWord* data) {
return FRC_NetworkCommunication_getControlWord((ControlWord_t*)data);
int HAL_GetControlWord(HAL_ControlWord* controlWord) {
std::memset(controlWord, 0, sizeof(HAL_ControlWord));
return FRC_NetworkCommunication_getControlWord(
reinterpret_cast<ControlWord_t*>(controlWord));
}
void HAL_SetNewDataSem(MULTIWAIT_ID sem) {
setNewDataSem(sem->native_handle());
}
int HAL_GetAllianceStation(enum HAL_AllianceStationID* allianceStation) {
return FRC_NetworkCommunication_getAllianceStation(
(AllianceStationID_t*)allianceStation);
HAL_AllianceStationID HAL_GetAllianceStation(int32_t* status) {
HAL_AllianceStationID allianceStation;
*status = FRC_NetworkCommunication_getAllianceStation(
reinterpret_cast<AllianceStationID_t*>(&allianceStation));
return allianceStation;
}
int HAL_GetJoystickAxes(uint8_t joystickNum, HAL_JoystickAxes* axes) {
@@ -142,27 +146,29 @@ int HAL_SetJoystickOutputs(uint8_t joystickNum, uint32_t outputs,
leftRumble, rightRumble);
}
int HAL_GetMatchTime(float* matchTime) {
return FRC_NetworkCommunication_getMatchTime(matchTime);
float HAL_GetMatchTime(int32_t* status) {
float matchTime;
*status = FRC_NetworkCommunication_getMatchTime(&matchTime);
return matchTime;
}
void HAL_NetworkCommunicationObserveUserProgramStarting(void) {
void HAL_ObserveUserProgramStarting(void) {
FRC_NetworkCommunication_observeUserProgramStarting();
}
void HAL_NetworkCommunicationObserveUserProgramDisabled(void) {
void HAL_ObserveUserProgramDisabled(void) {
FRC_NetworkCommunication_observeUserProgramDisabled();
}
void HAL_NetworkCommunicationObserveUserProgramAutonomous(void) {
void HAL_ObserveUserProgramAutonomous(void) {
FRC_NetworkCommunication_observeUserProgramAutonomous();
}
void HAL_NetworkCommunicationObserveUserProgramTeleop(void) {
void HAL_ObserveUserProgramTeleop(void) {
FRC_NetworkCommunication_observeUserProgramTeleop();
}
void HAL_NetworkCommunicationObserveUserProgramTest(void) {
void HAL_ObserveUserProgramTest(void) {
FRC_NetworkCommunication_observeUserProgramTest();
}

View File

@@ -88,11 +88,10 @@ void DriverStation::Run() {
MotorSafetyHelper::CheckMotors();
period = 0;
}
if (m_userInDisabled) HAL_NetworkCommunicationObserveUserProgramDisabled();
if (m_userInAutonomous)
HAL_NetworkCommunicationObserveUserProgramAutonomous();
if (m_userInTeleop) HAL_NetworkCommunicationObserveUserProgramTeleop();
if (m_userInTest) HAL_NetworkCommunicationObserveUserProgramTest();
if (m_userInDisabled) HAL_ObserveUserProgramDisabled();
if (m_userInAutonomous) HAL_ObserveUserProgramAutonomous();
if (m_userInTeleop) HAL_ObserveUserProgramTeleop();
if (m_userInTest) HAL_ObserveUserProgramTest();
}
}
@@ -381,7 +380,6 @@ bool DriverStation::GetStickButton(uint32_t stick, uint8_t button) {
*/
bool DriverStation::IsEnabled() const {
HAL_ControlWord controlWord;
std::memset(&controlWord, 0, sizeof(controlWord));
HAL_GetControlWord(&controlWord);
return controlWord.enabled && controlWord.dsAttached;
}
@@ -393,7 +391,6 @@ bool DriverStation::IsEnabled() const {
*/
bool DriverStation::IsDisabled() const {
HAL_ControlWord controlWord;
std::memset(&controlWord, 0, sizeof(controlWord));
HAL_GetControlWord(&controlWord);
return !(controlWord.enabled && controlWord.dsAttached);
}
@@ -405,7 +402,6 @@ bool DriverStation::IsDisabled() const {
*/
bool DriverStation::IsAutonomous() const {
HAL_ControlWord controlWord;
std::memset(&controlWord, 0, sizeof(controlWord));
HAL_GetControlWord(&controlWord);
return controlWord.autonomous;
}
@@ -417,7 +413,6 @@ bool DriverStation::IsAutonomous() const {
*/
bool DriverStation::IsOperatorControl() const {
HAL_ControlWord controlWord;
std::memset(&controlWord, 0, sizeof(controlWord));
HAL_GetControlWord(&controlWord);
return !(controlWord.autonomous || controlWord.test);
}
@@ -440,7 +435,6 @@ bool DriverStation::IsTest() const {
*/
bool DriverStation::IsDSAttached() const {
HAL_ControlWord controlWord;
std::memset(&controlWord, 0, sizeof(controlWord));
HAL_GetControlWord(&controlWord);
return controlWord.dsAttached;
}
@@ -505,8 +499,8 @@ bool DriverStation::IsFMSAttached() const {
* @return The Alliance enum (kRed, kBlue or kInvalid)
*/
DriverStation::Alliance DriverStation::GetAlliance() const {
HAL_AllianceStationID allianceStationID;
HAL_GetAllianceStation(&allianceStationID);
int32_t status = 0;
auto allianceStationID = HAL_GetAllianceStation(&status);
switch (allianceStationID) {
case HAL_AllianceStationID_kRed1:
case HAL_AllianceStationID_kRed2:
@@ -529,8 +523,8 @@ DriverStation::Alliance DriverStation::GetAlliance() const {
* @return The location of the driver station (1-3, 0 for invalid)
*/
uint32_t DriverStation::GetLocation() const {
HAL_AllianceStationID allianceStationID;
HAL_GetAllianceStation(&allianceStationID);
int32_t status = 0;
auto allianceStationID = HAL_GetAllianceStation(&status);
switch (allianceStationID) {
case HAL_AllianceStationID_kRed1:
case HAL_AllianceStationID_kBlue1:
@@ -578,9 +572,8 @@ void DriverStation::WaitForData() {
* @return Time remaining in current match period (auto or teleop)
*/
double DriverStation::GetMatchTime() const {
float matchTime;
HAL_GetMatchTime(&matchTime);
return (double)matchTime;
int32_t status;
return HAL_GetMatchTime(&status);
}
/**

View File

@@ -34,7 +34,7 @@ void IterativeRobot::StartCompetition() {
RobotInit();
// Tell the DS that the robot is ready to be enabled
HAL_NetworkCommunicationObserveUserProgramStarting();
HAL_ObserveUserProgramStarting();
// loop forever, calling the appropriate mode-dependent function
lw->SetEnabled(false);
@@ -52,7 +52,7 @@ void IterativeRobot::StartCompetition() {
m_teleopInitialized = false;
m_testInitialized = false;
}
HAL_NetworkCommunicationObserveUserProgramDisabled();
HAL_ObserveUserProgramDisabled();
DisabledPeriodic();
} else if (IsAutonomous()) {
// call AutonomousInit() if we are now just entering autonomous mode from
@@ -66,7 +66,7 @@ void IterativeRobot::StartCompetition() {
m_teleopInitialized = false;
m_testInitialized = false;
}
HAL_NetworkCommunicationObserveUserProgramAutonomous();
HAL_ObserveUserProgramAutonomous();
AutonomousPeriodic();
} else if (IsTest()) {
// call TestInit() if we are now just entering test mode from
@@ -80,7 +80,7 @@ void IterativeRobot::StartCompetition() {
m_autonomousInitialized = false;
m_teleopInitialized = false;
}
HAL_NetworkCommunicationObserveUserProgramTest();
HAL_ObserveUserProgramTest();
TestPeriodic();
} else {
// call TeleopInit() if we are now just entering teleop mode from
@@ -95,7 +95,7 @@ void IterativeRobot::StartCompetition() {
m_testInitialized = false;
Scheduler::GetInstance()->SetEnabled(true);
}
HAL_NetworkCommunicationObserveUserProgramTeleop();
HAL_ObserveUserProgramTeleop();
TeleopPeriodic();
}
// wait for driver station data so the loop doesn't hog the CPU

View File

@@ -112,7 +112,7 @@ void SampleRobot::StartCompetition() {
RobotInit();
// Tell the DS that the robot is ready to be enabled
HAL_NetworkCommunicationObserveUserProgramStarting();
HAL_ObserveUserProgramStarting();
RobotMain();

View File

@@ -30,7 +30,7 @@ class TestEnvironment : public testing::Environment {
station. After starting network coms, it will loop until the driver
station returns that the robot is enabled, to ensure that tests
will be able to run on the hardware. */
HAL_NetworkCommunicationObserveUserProgramStarting();
HAL_ObserveUserProgramStarting();
LiveWindow::GetInstance()->SetEnabled(false);
std::cout << "Waiting for enable" << std::endl;

View File

@@ -153,7 +153,8 @@ task jniHeaders {
args '-d', outputFolder
args '-classpath', sourceSets.athena.output.classesDir
args 'edu.wpi.first.wpilibj.can.CANJNI'
args 'edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary'
args 'edu.wpi.first.wpilibj.hal.FRCNetComm'
args 'edu.wpi.first.wpilibj.hal.HAL'
args 'edu.wpi.first.wpilibj.hal.HALUtil'
args 'edu.wpi.first.wpilibj.hal.JNIWrapper'
args 'edu.wpi.first.wpilibj.hal.AccelerometerJNI'

View File

@@ -29,14 +29,14 @@ extern "C" {
/*
* Class: edu_wpi_first_wpilibj_can_CANJNI
* Method: FRCNetworkCommunicationCANSessionMuxSendMessage
* Method: FRCNetCommCANSessionMuxSendMessage
* Signature: (ILjava/nio/ByteBuffer;I)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetworkCommunicationCANSessionMuxSendMessage(
Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetCommCANSessionMuxSendMessage(
JNIEnv *env, jclass, jint messageID, jobject data, jint periodMs) {
CANJNI_LOG(logDEBUG)
<< "Calling CANJNI FRCNetworkCommunicationCANSessionMuxSendMessage";
<< "Calling CANJNI FRCNetCommCANSessionMuxSendMessage";
uint8_t *dataBuffer =
(uint8_t *)(data ? env->GetDirectBufferAddress(data) : 0);
@@ -72,15 +72,15 @@ static uint8_t buffer[8];
/*
* Class: edu_wpi_first_wpilibj_can_CANJNI
* Method: FRCNetworkCommunicationCANSessionMuxReceiveMessage
* Method: FRCNetCommCANSessionMuxReceiveMessage
* Signature: (Ljava/nio/IntBuffer;ILjava/nio/ByteBuffer;)Ljava/nio/ByteBuffer;
*/
JNIEXPORT jobject JNICALL
Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetworkCommunicationCANSessionMuxReceiveMessage(
Java_edu_wpi_first_wpilibj_can_CANJNI_FRCNetCommCANSessionMuxReceiveMessage(
JNIEnv *env, jclass, jobject messageID, jint messageIDMask,
jobject timeStamp) {
CANJNI_LOG(logDEBUG)
<< "Calling CANJNI FRCNetworkCommunicationCANSessionMuxReceiveMessage";
<< "Calling CANJNI FRCNetCommCANSessionMuxReceiveMessage";
uint32_t *messageIDPtr = (uint32_t *)env->GetDirectBufferAddress(messageID);
uint32_t *timeStampPtr = (uint32_t *)env->GetDirectBufferAddress(timeStamp);

View File

@@ -1,368 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) FIRST 2016. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include <assert.h>
#include <jni.h>
#include "Log.h"
#include "HAL/HAL.h"
#include "edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary.h"
#include "HALUtil.h"
// set the logging level
TLogLevel netCommLogLevel = logWARNING;
#define NETCOMM_LOG(level) \
if (level > netCommLogLevel) \
; \
else \
Log().Get(level)
extern "C" {
/*
* Class: edu_wpi_first_wpilibj_communication_FRC_NetworkCommunicationsLibrary
* Method: FRC_NetworkCommunication_nUsageReporting_report
* Signature: (BBBLjava/lang/String;)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_FRCNetworkCommunicationUsageReportingReport(
JNIEnv *paramEnv, jclass, jbyte paramResource, jbyte paramInstanceNumber,
jbyte paramContext, jstring paramFeature) {
const char *featureStr = paramEnv->GetStringUTFChars(paramFeature, nullptr);
NETCOMM_LOG(logDEBUG) << "Calling FRCNetworkCommunicationsLibrary report "
<< "res:" << (unsigned int)paramResource
<< " instance:" << (unsigned int)paramInstanceNumber
<< " context:" << (unsigned int)paramContext
<< " feature:" << featureStr;
jint returnValue =
HAL_Report(paramResource, paramInstanceNumber, paramContext, featureStr);
paramEnv->ReleaseStringUTFChars(paramFeature, featureStr);
return returnValue;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRC_NetworkCommunicationsLibrary
* Method: FRC_NetworkCommunication_observeUserProgramStarting
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_FRCNetworkCommunicationObserveUserProgramStarting(
JNIEnv *, jclass) {
HAL_NetworkCommunicationObserveUserProgramStarting();
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRC_NetworkCommunicationsLibrary
* Method: FRC_NetworkCommunication_observeUserProgramDisabled
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_FRCNetworkCommunicationObserveUserProgramDisabled(
JNIEnv *, jclass) {
HAL_NetworkCommunicationObserveUserProgramDisabled();
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRC_NetworkCommunicationsLibrary
* Method: FRC_NetworkCommunication_observeUserProgramAutonomous
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_FRCNetworkCommunicationObserveUserProgramAutonomous(
JNIEnv *, jclass) {
HAL_NetworkCommunicationObserveUserProgramAutonomous();
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRC_NetworkCommunicationsLibrary
* Method: FRC_NetworkCommunication_observeUserProgramTeleop
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_FRCNetworkCommunicationObserveUserProgramTeleop(
JNIEnv *, jclass) {
HAL_NetworkCommunicationObserveUserProgramTeleop();
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRC_NetworkCommunicationsLibrary
* Method: FRC_NetworkCommunication_observeUserProgramTest
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_FRCNetworkCommunicationObserveUserProgramTest(
JNIEnv *, jclass) {
HAL_NetworkCommunicationObserveUserProgramTest();
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: FRCNetworkCommunicationReserve
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_FRCNetworkCommunicationReserve(
JNIEnv *, jclass) {
int rv = HAL_Initialize(0);
assert(1 == rv);
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: NativeHALGetControlWord
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_NativeHALGetControlWord(
JNIEnv *, jclass) {
NETCOMM_LOG(logDEBUG) << "Calling HAL Control Word";
jint controlWord;
HAL_GetControlWord((HAL_ControlWord *)&controlWord);
return controlWord;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: NativeHALGetAllianceStation
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_NativeHALGetAllianceStation(
JNIEnv *, jclass) {
NETCOMM_LOG(logDEBUG) << "Calling HAL Alliance Station";
jint allianceStation;
HAL_GetAllianceStation((HAL_AllianceStationID *)&allianceStation);
return allianceStation;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetJoystickAxes
* Signature: (B[S)B
*/
JNIEXPORT jbyte JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetJoystickAxes(
JNIEnv * env, jclass, jbyte joystickNum, jfloatArray axesArray) {
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickAxes";
HAL_JoystickAxes axes;
HAL_GetJoystickAxes(joystickNum, &axes);
jsize javaSize = env->GetArrayLength(axesArray);
if (axes.count > javaSize)
{
ThrowIllegalArgumentException(env, "Native array size larger then passed in java array size");
}
env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
return axes.count;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetJoystickPOVs
* Signature: (B[S)B
*/
JNIEXPORT jbyte JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetJoystickPOVs(
JNIEnv * env, jclass, jbyte joystickNum, jshortArray povsArray) {
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickPOVs";
HAL_JoystickPOVs povs;
HAL_GetJoystickPOVs(joystickNum, &povs);
jsize javaSize = env->GetArrayLength(povsArray);
if (povs.count > javaSize)
{
ThrowIllegalArgumentException(env, "Native array size larger then passed in java array size");
}
env->SetShortArrayRegion(povsArray, 0, povs.count, povs.povs);
return povs.count;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetJoystickButtons
* Signature: (B)S
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetJoystickButtons(
JNIEnv *env, jclass, jbyte joystickNum, jobject count) {
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickButtons";
HAL_JoystickButtons joystickButtons;
HAL_GetJoystickButtons(joystickNum, &joystickButtons);
jbyte *countPtr = (jbyte *)env->GetDirectBufferAddress(count);
NETCOMM_LOG(logDEBUG) << "Buttons = " << joystickButtons.buttons;
NETCOMM_LOG(logDEBUG) << "Count = " << (jint)joystickButtons.count;
*countPtr = joystickButtons.count;
NETCOMM_LOG(logDEBUG) << "CountBuffer = " << (jint)*countPtr;
return joystickButtons.buttons;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_SetJoystickOutputs
* Signature: (BISS)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALSetJoystickOutputs(
JNIEnv *, jclass, jbyte port, jint outputs, jshort leftRumble,
jshort rightRumble) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_SetJoystickOutputs on port " << port;
NETCOMM_LOG(logDEBUG) << "Outputs: " << outputs;
NETCOMM_LOG(logDEBUG) << "Left Rumble: " << leftRumble
<< " Right Rumble: " << rightRumble;
return HAL_SetJoystickOutputs(port, outputs, leftRumble, rightRumble);
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetJoystickIsXbox
* Signature: (B)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetJoystickIsXbox(
JNIEnv *, jclass, jbyte port) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickIsXbox";
return HAL_GetJoystickIsXbox(port);
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetJoystickType
* Signature: (B)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetJoystickType(
JNIEnv *, jclass, jbyte port) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickType";
return HAL_GetJoystickType(port);
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetJoystickName
* Signature: (B)Ljava/lang/String;
*/
JNIEXPORT jstring JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetJoystickName(
JNIEnv *env, jclass, jbyte port) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickName";
char *joystickName = HAL_GetJoystickName(port);
jstring str = env->NewStringUTF(joystickName);
std::free(joystickName);
return str;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetJoystickAxisType
* Signature: (BB)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetJoystickAxisType(
JNIEnv *, jclass, jbyte joystickNum, jbyte axis) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickAxisType";
return HAL_GetJoystickAxisType(joystickNum, axis);
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: setNewDataSem
* Signature: (J)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_setNewDataSem(
JNIEnv *env, jclass, jlong id) {
NETCOMM_LOG(logDEBUG) << "Mutex Ptr = " << (void *)id;
HAL_SetNewDataSem((MULTIWAIT_ID)id);
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetMatchTime
* Signature: ()F
*/
JNIEXPORT jfloat JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetMatchTime(
JNIEnv *env, jclass) {
jfloat matchTime;
HAL_GetMatchTime((float *)&matchTime);
return matchTime;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetSystemActive
* Signature: ()Z
*/
JNIEXPORT jboolean JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetSystemActive(
JNIEnv *env, jclass) {
int32_t status = 0;
bool val = HAL_GetSystemActive(&status);
CheckStatus(env, status);
return val;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_GetBrownedOut
* Signature: ()Z
*/
JNIEXPORT jboolean JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALGetBrownedOut(
JNIEnv *env, jclass) {
int32_t status = 0;
bool val = HAL_GetBrownedOut(&status);
CheckStatus(env, status);
return val;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_SetErrorData
* Signature: (Ljava/lang/String;)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALSetErrorData(
JNIEnv *env, jclass, jstring error) {
const char *errorStr = env->GetStringUTFChars(error, nullptr);
jsize length = env->GetStringUTFLength(error);
NETCOMM_LOG(logDEBUG) << "Set Error: " << errorStr;
NETCOMM_LOG(logDEBUG) << "Length: " << length;
jint returnValue = HAL_SetErrorData(errorStr, (jint)length, 0);
env->ReleaseStringUTFChars(error, errorStr);
return returnValue;
}
/*
* Class: edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary
* Method: HAL_SendError
* Signature: (ZIZLjava/lang/String;Ljava/lang/String;Ljava/lang/String;Z)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_communication_FRCNetworkCommunicationsLibrary_HALSendError(
JNIEnv *env, jclass, jboolean isError, jint errorCode, jboolean isLVCode,
jstring details, jstring location, jstring callStack, jboolean printMsg) {
const char *detailsStr = env->GetStringUTFChars(details, nullptr);
const char *locationStr = env->GetStringUTFChars(location, nullptr);
const char *callStackStr = env->GetStringUTFChars(callStack, nullptr);
NETCOMM_LOG(logDEBUG) << "Send Error: " << detailsStr;
NETCOMM_LOG(logDEBUG) << "Location: " << locationStr;
NETCOMM_LOG(logDEBUG) << "Call Stack: " << callStackStr;
jint returnValue = HAL_SendError(isError, errorCode, isLVCode, detailsStr,
locationStr, callStackStr, printMsg);
env->ReleaseStringUTFChars(details, detailsStr);
env->ReleaseStringUTFChars(location, locationStr);
env->ReleaseStringUTFChars(callStack, callStackStr);
return returnValue;
}
} // extern "C"

View File

@@ -0,0 +1,369 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) FIRST 2016. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#include <cstring>
#include <assert.h>
#include <jni.h>
#include "Log.h"
#include "HAL/HAL.h"
#include "edu_wpi_first_wpilibj_hal_HAL.h"
#include "HALUtil.h"
// set the logging level
static TLogLevel netCommLogLevel = logWARNING;
#define NETCOMM_LOG(level) \
if (level > netCommLogLevel) \
; \
else \
Log().Get(level)
extern "C" {
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: Initialize
* Signature: (I)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_initialize(JNIEnv*, jclass, jint mode) {
return HAL_Initialize(mode);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: observeUserProgramStarting
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramStarting(JNIEnv*, jclass) {
HAL_ObserveUserProgramStarting();
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: observeUserProgramDisabled
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramDisabled(JNIEnv*, jclass) {
HAL_ObserveUserProgramDisabled();
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: observeUserProgramAutonomous
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramAutonomous(
JNIEnv*, jclass) {
HAL_ObserveUserProgramAutonomous();
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: observeUserProgramTeleop
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramTeleop(JNIEnv*, jclass) {
HAL_ObserveUserProgramTeleop();
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: observeUserProgramTest
* Signature: ()V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_observeUserProgramTest(JNIEnv*, jclass) {
HAL_ObserveUserProgramTest();
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_Report
* Signature: (IIILjava/lang/String;)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_report(
JNIEnv* paramEnv, jclass, jint paramResource, jint paramInstanceNumber,
jint paramContext, jstring paramFeature) {
const char *featureStr = paramEnv->GetStringUTFChars(paramFeature, nullptr);
NETCOMM_LOG(logDEBUG) << "Calling HAL report "
<< "res:" << paramResource
<< " instance:" << paramInstanceNumber
<< " context:" << paramContext
<< " feature:" << featureStr;
jint returnValue =
HAL_Report(paramResource, paramInstanceNumber, paramContext, featureStr);
paramEnv->ReleaseStringUTFChars(paramFeature, featureStr);
return returnValue;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: NativeGetControlWord
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_nativeGetControlWord(JNIEnv*, jclass) {
NETCOMM_LOG(logDEBUG) << "Calling HAL Control Word";
HAL_ControlWord controlWord;
std::memset(&controlWord, 0, sizeof(HAL_ControlWord));
HAL_GetControlWord(&controlWord);
return *reinterpret_cast<jint*>(&controlWord);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: NativeGetAllianceStation
* Signature: ()I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_nativeGetAllianceStation(JNIEnv*, jclass) {
NETCOMM_LOG(logDEBUG) << "Calling HAL Alliance Station";
int32_t status = 0;
auto allianceStation = HAL_GetAllianceStation(&status);
return *reinterpret_cast<jint*>(&allianceStation);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetJoystickAxes
* Signature: (B[S)S
*/
JNIEXPORT jshort JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickAxes(JNIEnv* env, jclass,
jbyte joystickNum,
jfloatArray axesArray) {
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickAxes";
HAL_JoystickAxes axes;
HAL_GetJoystickAxes(joystickNum, &axes);
jsize javaSize = env->GetArrayLength(axesArray);
if (axes.count > javaSize)
{
ThrowIllegalArgumentException(env, "Native array size larger then passed in java array size");
}
env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
return axes.count;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetJoystickPOVs
* Signature: (B[S)S
*/
JNIEXPORT jshort JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickPOVs(JNIEnv* env, jclass,
jbyte joystickNum,
jshortArray povsArray) {
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickPOVs";
HAL_JoystickPOVs povs;
HAL_GetJoystickPOVs(joystickNum, &povs);
jsize javaSize = env->GetArrayLength(povsArray);
if (povs.count > javaSize)
{
ThrowIllegalArgumentException(env, "Native array size larger then passed in java array size");
}
env->SetShortArrayRegion(povsArray, 0, povs.count, povs.povs);
return povs.count;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetJoystickButtons
* Signature: (B)B
*/
JNIEXPORT jbyte JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickButtons(JNIEnv* env, jclass,
jbyte joystickNum,
jobject count) {
NETCOMM_LOG(logDEBUG) << "Calling HALJoystickButtons";
HAL_JoystickButtons joystickButtons;
HAL_GetJoystickButtons(joystickNum, &joystickButtons);
jbyte *countPtr = (jbyte *)env->GetDirectBufferAddress(count);
NETCOMM_LOG(logDEBUG) << "Buttons = " << joystickButtons.buttons;
NETCOMM_LOG(logDEBUG) << "Count = " << (jint)joystickButtons.count;
*countPtr = joystickButtons.count;
NETCOMM_LOG(logDEBUG) << "CountBuffer = " << (jint)*countPtr;
return joystickButtons.buttons;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_SetJoystickOutputs
* Signature: (BISS)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_setJoystickOutputs(JNIEnv*, jclass,
jbyte port, jint outputs,
jshort leftRumble,
jshort rightRumble) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_SetJoystickOutputs on port " << port;
NETCOMM_LOG(logDEBUG) << "Outputs: " << outputs;
NETCOMM_LOG(logDEBUG) << "Left Rumble: " << leftRumble
<< " Right Rumble: " << rightRumble;
return HAL_SetJoystickOutputs(port, outputs, leftRumble, rightRumble);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetJoystickIsXbox
* Signature: (B)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickIsXbox(JNIEnv*, jclass,
jbyte port) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickIsXbox";
return HAL_GetJoystickIsXbox(port);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetJoystickType
* Signature: (B)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickType(JNIEnv*, jclass,
jbyte port) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickType";
return HAL_GetJoystickType(port);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetJoystickName
* Signature: (B)Ljava/lang/String;
*/
JNIEXPORT jstring JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickName(JNIEnv* env, jclass,
jbyte port) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickName";
char *joystickName = HAL_GetJoystickName(port);
jstring str = env->NewStringUTF(joystickName);
std::free(joystickName);
return str;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetJoystickAxisType
* Signature: (BB)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getJoystickAxisType(JNIEnv*, jclass,
jbyte joystickNum,
jbyte axis) {
NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickAxisType";
return HAL_GetJoystickAxisType(joystickNum, axis);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HALSetNewDataSem
* Signature: (J)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_setNewDataSem(JNIEnv* env, jclass,
jlong id) {
NETCOMM_LOG(logDEBUG) << "Mutex Ptr = " << (void *)id;
HAL_SetNewDataSem((MULTIWAIT_ID)id);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetMatchTime
* Signature: ()F
*/
JNIEXPORT jfloat JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getMatchTime(JNIEnv* env, jclass) {
int32_t status = 0;
return HAL_GetMatchTime(&status);
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetSystemActive
* Signature: ()Z
*/
JNIEXPORT jboolean JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getSystemActive(JNIEnv* env, jclass) {
int32_t status = 0;
bool val = HAL_GetSystemActive(&status);
CheckStatus(env, status);
return val;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_GetBrownedOut
* Signature: ()Z
*/
JNIEXPORT jboolean JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_getBrownedOut(JNIEnv* env, jclass) {
int32_t status = 0;
bool val = HAL_GetBrownedOut(&status);
CheckStatus(env, status);
return val;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_SetErrorData
* Signature: (Ljava/lang/String;)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_setErrorData(JNIEnv* env, jclass,
jstring error) {
const char *errorStr = env->GetStringUTFChars(error, nullptr);
jsize length = env->GetStringUTFLength(error);
NETCOMM_LOG(logDEBUG) << "Set Error: " << errorStr;
NETCOMM_LOG(logDEBUG) << "Length: " << length;
jint returnValue = HAL_SetErrorData(errorStr, (jint)length, 0);
env->ReleaseStringUTFChars(error, errorStr);
return returnValue;
}
/*
* Class: edu_wpi_first_wpilibj_hal_HAL
* Method: HAL_SendError
* Signature: (ZIZLjava/lang/String;Ljava/lang/String;Ljava/lang/String;Z)I
*/
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_HAL_sendError(JNIEnv* env, jclass,
jboolean isError, jint errorCode,
jboolean isLVCode, jstring details,
jstring location,
jstring callStack,
jboolean printMsg) {
const char *detailsStr = env->GetStringUTFChars(details, nullptr);
const char *locationStr = env->GetStringUTFChars(location, nullptr);
const char *callStackStr = env->GetStringUTFChars(callStack, nullptr);
NETCOMM_LOG(logDEBUG) << "Send Error: " << detailsStr;
NETCOMM_LOG(logDEBUG) << "Location: " << locationStr;
NETCOMM_LOG(logDEBUG) << "Call Stack: " << callStackStr;
jint returnValue = HAL_SendError(isError, errorCode, isLVCode, detailsStr,
locationStr, callStackStr, printMsg);
env->ReleaseStringUTFChars(details, detailsStr);
env->ReleaseStringUTFChars(location, locationStr);
env->ReleaseStringUTFChars(callStack, callStackStr);
return returnValue;
}
} // extern "C"

View File

@@ -10,9 +10,9 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -91,7 +91,7 @@ public class ADXL345_I2C extends SensorBase implements Accelerometer, LiveWindow
setRange(range);
UsageReporting.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C);
HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C);
LiveWindow.addSensor("ADXL345_I2C", port.getValue(), this);
}

View File

@@ -10,9 +10,9 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -104,7 +104,7 @@ public class ADXL345_SPI extends SensorBase implements Accelerometer, LiveWindow
setRange(range);
UsageReporting.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_SPI);
HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_SPI);
}
@Override

View File

@@ -10,8 +10,8 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -110,7 +110,7 @@ public class ADXL362 extends SensorBase implements Accelerometer, LiveWindowSend
transferBuffer.put(2, (byte) (kPowerCtl_Measure | kPowerCtl_UltraLowNoise));
m_spi.write(transferBuffer, 3);
UsageReporting.report(tResourceType.kResourceType_ADXL362, port.getValue());
HAL.report(tResourceType.kResourceType_ADXL362, port.getValue());
LiveWindow.addSensor("ADXL362", port.getValue(), this);
}

View File

@@ -10,8 +10,8 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.interfaces.Gyro;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -77,7 +77,7 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, LiveWind
calibrate();
UsageReporting.report(tResourceType.kResourceType_ADXRS450, port.getValue());
HAL.report(tResourceType.kResourceType_ADXRS450, port.getValue());
LiveWindow.addSensor("ADXRS450_Gyro", port.getValue(), this);
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
@@ -31,7 +31,8 @@ public class AnalogAccelerometer extends SensorBase implements PIDSource, LiveWi
* Common initialization.
*/
private void initAccelerometer() {
UsageReporting.report(tResourceType.kResourceType_Accelerometer, m_analogChannel.getChannel());
HAL.report(tResourceType.kResourceType_Accelerometer,
m_analogChannel.getChannel());
LiveWindow.addSensor("Accelerometer", m_analogChannel.getChannel(), this);
}

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.AnalogGyroJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.interfaces.Gyro;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -42,7 +42,7 @@ public class AnalogGyro extends GyroBase implements Gyro, PIDSource, LiveWindowS
AnalogGyroJNI.setupAnalogGyro(m_gyroHandle);
UsageReporting.report(tResourceType.kResourceType_Gyro, m_analog.getChannel());
HAL.report(tResourceType.kResourceType_Gyro, m_analog.getChannel());
LiveWindow.addSensor("AnalogGyro", m_analog.getChannel(), this);
}

View File

@@ -10,9 +10,9 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.AnalogJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
@@ -56,7 +56,7 @@ public class AnalogInput extends SensorBase implements PIDSource, LiveWindowSend
m_port = AnalogJNI.initializeAnalogInputPort(portHandle);
LiveWindow.addSensor("AnalogInput", channel, this);
UsageReporting.report(tResourceType.kResourceType_AnalogChannel, channel);
HAL.report(tResourceType.kResourceType_AnalogChannel, channel);
}
/**

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.AnalogJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
@@ -39,7 +39,7 @@ public class AnalogOutput extends SensorBase implements LiveWindowSendable {
m_port = AnalogJNI.initializeAnalogOutputPort(portHandle);
LiveWindow.addSensor("AnalogOutput", channel, this);
UsageReporting.report(tResourceType.kResourceType_AnalogOutput, channel);
HAL.report(tResourceType.kResourceType_AnalogOutput, channel);
}
/**

View File

@@ -11,9 +11,9 @@ import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.AnalogJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.util.BoundaryException;
import static java.util.Objects.requireNonNull;
@@ -72,7 +72,7 @@ public class AnalogTrigger {
AnalogJNI.initializeAnalogTrigger(channel.m_port, index.asIntBuffer());
m_index = index.asIntBuffer().get(0);
UsageReporting.report(tResourceType.kResourceType_AnalogTrigger, channel.getChannel());
HAL.report(tResourceType.kResourceType_AnalogTrigger, channel.getChannel());
}
/**

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.AnalogJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
/**
* Class to represent a specific output from an analog trigger. This class is used to get the
@@ -77,8 +77,8 @@ public class AnalogTriggerOutput extends DigitalSource {
m_trigger = trigger;
m_outputType = outputType;
UsageReporting.report(tResourceType.kResourceType_AnalogTriggerOutput, trigger.getIndex(),
outputType.m_value);
HAL.report(tResourceType.kResourceType_AnalogTriggerOutput,
trigger.getIndex(), outputType.m_value);
}
/**

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.AccelerometerJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.interfaces.Accelerometer;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -28,8 +28,7 @@ public class BuiltInAccelerometer implements Accelerometer, LiveWindowSendable {
*/
public BuiltInAccelerometer(Range range) {
setRange(range);
UsageReporting
.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer");
HAL.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer");
LiveWindow.addSensor("BuiltInAccel", 0, this);
}

View File

@@ -307,7 +307,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, CANSpeedController {
return;
}
CANJNI.FRCNetworkCommunicationCANSessionMuxSendMessage(messageID, null,
CANJNI.FRCNetCommCANSessionMuxSendMessage(messageID, null,
CANJNI.CAN_SEND_PERIOD_STOP_REPEATING);
configMaxOutputVoltage(kApproxBusVoltage);
@@ -1918,7 +1918,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, CANSpeedController {
trustedBuffer.put(j + 2, data[j]);
}
CANJNI.FRCNetworkCommunicationCANSessionMuxSendMessage(messageID, trustedBuffer, period);
CANJNI.FRCNetCommCANSessionMuxSendMessage(messageID, trustedBuffer, period);
return;
}
@@ -1935,7 +1935,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, CANSpeedController {
buffer = null;
}
CANJNI.FRCNetworkCommunicationCANSessionMuxSendMessage(messageID, buffer, period);
CANJNI.FRCNetCommCANSessionMuxSendMessage(messageID, buffer, period);
}
/**
@@ -2004,7 +2004,7 @@ public class CANJaguar implements MotorSafety, PIDOutput, CANSpeedController {
// Get the data.
ByteBuffer dataBuffer =
CANJNI.FRCNetworkCommunicationCANSessionMuxReceiveMessage(targetedMessageID.asIntBuffer(),
CANJNI.FRCNetCommCANSessionMuxReceiveMessage(targetedMessageID.asIntBuffer(),
messageMask, timeStamp);
if (data != null) {

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.CanTalonJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.tables.ITable;
import edu.wpi.first.wpilibj.tables.ITableListener;
@@ -872,7 +872,7 @@ public class CANTalon implements MotorSafety, PIDOutput, PIDSource, CANSpeedCont
// Disable until set() is called.
CanTalonJNI.SetModeSelect(m_handle, TalonControlMode.Disabled.value);
UsageReporting.report(tResourceType.kResourceType_CANTalonSRX, m_deviceNumber + 1,
HAL.report(tResourceType.kResourceType_CANTalonSRX, m_deviceNumber + 1,
controlMode.value);
}

View File

@@ -11,9 +11,9 @@ import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.CounterJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
import edu.wpi.first.wpilibj.util.BoundaryException;
@@ -87,7 +87,7 @@ public class Counter extends SensorBase implements CounterBase, LiveWindowSendab
setMaxPeriod(.5);
UsageReporting.report(tResourceType.kResourceType_Counter, m_index, mode.value);
HAL.report(tResourceType.kResourceType_Counter, m_index, mode.value);
}
/**

View File

@@ -10,9 +10,9 @@ package edu.wpi.first.wpilibj;
import java.util.concurrent.locks.Lock;
import java.util.concurrent.locks.ReentrantLock;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.DigitalGlitchFilterJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
/**
* Class to enable glitch filtering on a set of digital inputs. This class will manage adding and
@@ -33,7 +33,7 @@ public class DigitalGlitchFilter extends SensorBase {
if (index != m_filterAllocated.length) {
m_channelIndex = index;
m_filterAllocated[index] = true;
UsageReporting.report(tResourceType.kResourceType_DigitalFilter,
HAL.report(tResourceType.kResourceType_DigitalFilter,
m_channelIndex, 0);
}
}

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.DIOJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
@@ -36,7 +36,7 @@ public class DigitalInput extends DigitalSource implements LiveWindowSendable {
m_handle = DIOJNI.initializeDIOPort(DIOJNI.getPort((byte)channel), true);
LiveWindow.addSensor("DigitalInput", channel, this);
UsageReporting.report(tResourceType.kResourceType_DigitalInput, channel);
HAL.report(tResourceType.kResourceType_DigitalInput, channel);
}
/**

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.DIOJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
import edu.wpi.first.wpilibj.tables.ITableListener;
@@ -39,7 +39,7 @@ public class DigitalOutput extends DigitalSource implements LiveWindowSendable {
m_handle = DIOJNI.initializeDIOPort(DIOJNI.getPort((byte)channel), false);
UsageReporting.report(tResourceType.kResourceType_DigitalOutput, channel);
HAL.report(tResourceType.kResourceType_DigitalOutput, channel);
}
/**

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.SolenoidJNI;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -85,8 +85,10 @@ public class DoubleSolenoid extends SolenoidBase implements LiveWindowSendable {
m_forwardMask = (byte) (1 << m_forwardChannel);
m_reverseMask = (byte) (1 << m_reverseChannel);
UsageReporting.report(tResourceType.kResourceType_Solenoid, m_forwardChannel, m_moduleNumber);
UsageReporting.report(tResourceType.kResourceType_Solenoid, m_reverseChannel, m_moduleNumber);
HAL.report(tResourceType.kResourceType_Solenoid, m_forwardChannel,
m_moduleNumber);
HAL.report(tResourceType.kResourceType_Solenoid, m_reverseChannel,
m_moduleNumber);
LiveWindow.addActuator("DoubleSolenoid", m_moduleNumber, m_forwardChannel, this);
}

View File

@@ -9,9 +9,9 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
import edu.wpi.first.wpilibj.communication.HALAllianceStationID;
import edu.wpi.first.wpilibj.communication.HALControlWord;
import edu.wpi.first.wpilibj.hal.AllianceStationID;
import edu.wpi.first.wpilibj.hal.ControlWord;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.HALUtil;
import edu.wpi.first.wpilibj.hal.PowerJNI;
@@ -32,7 +32,7 @@ public class DriverStation implements RobotState.Interface {
private class HALJoystickAxes {
public float[] m_axes;
public byte m_count;
public short m_count;
public HALJoystickAxes(int count) {
m_axes = new float[count];
@@ -41,7 +41,7 @@ public class DriverStation implements RobotState.Interface {
private class HALJoystickPOVs {
public short[] m_povs;
public byte m_count;
public short m_count;
public HALJoystickPOVs(int count) {
m_povs = new short[count];
@@ -86,8 +86,7 @@ public class DriverStation implements RobotState.Interface {
private int[] m_joystickIsXbox = new int[kJoystickPorts];
private int[] m_joystickType = new int[kJoystickPorts];
private String[] m_joystickName = new String[kJoystickPorts];
private int[][] m_joystickAxisType =
new int[kJoystickPorts][FRCNetworkCommunicationsLibrary.kMaxJoystickAxes];
private int[][] m_joystickAxisType = new int[kJoystickPorts][HAL.kMaxJoystickAxes];
private Thread m_thread;
private final Object m_dataSem;
@@ -125,19 +124,17 @@ public class DriverStation implements RobotState.Interface {
m_newControlDataMutex = new Object();
for (int i = 0; i < kJoystickPorts; i++) {
m_joystickButtons[i] = new HALJoystickButtons();
m_joystickAxes[i] = new HALJoystickAxes(FRCNetworkCommunicationsLibrary.kMaxJoystickAxes);
m_joystickPOVs[i] = new HALJoystickPOVs(FRCNetworkCommunicationsLibrary.kMaxJoystickPOVs);
m_joystickAxes[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes);
m_joystickPOVs[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs);
m_joystickButtonsCache[i] = new HALJoystickButtons();
m_joystickAxesCache[i] =
new HALJoystickAxes(FRCNetworkCommunicationsLibrary.kMaxJoystickAxes);
m_joystickPOVsCache[i] =
new HALJoystickPOVs(FRCNetworkCommunicationsLibrary.kMaxJoystickPOVs);
m_joystickAxesCache[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes);
m_joystickPOVsCache[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs);
}
m_packetDataAvailableMutex = HALUtil.initializeMutexNormal();
m_packetDataAvailableSem = HALUtil.initializeMultiWait();
FRCNetworkCommunicationsLibrary.setNewDataSem(m_packetDataAvailableSem);
HAL.setNewDataSem(m_packetDataAvailableSem);
m_thread = new Thread(new DriverStationTask(this), "FRCDriverStation");
m_thread.setPriority((Thread.NORM_PRIORITY + Thread.MAX_PRIORITY) / 2);
@@ -169,16 +166,16 @@ public class DriverStation implements RobotState.Interface {
safetyCounter = 0;
}
if (m_userInDisabled) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramDisabled();
HAL.observeUserProgramDisabled();
}
if (m_userInAutonomous) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramAutonomous();
HAL.observeUserProgramAutonomous();
}
if (m_userInTeleop) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTeleop();
HAL.observeUserProgramTeleop();
}
if (m_userInTest) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTest();
HAL.observeUserProgramTest();
}
}
}
@@ -217,13 +214,10 @@ public class DriverStation implements RobotState.Interface {
// Get the status of all of the joysticks
for (byte stick = 0; stick < kJoystickPorts; stick++) {
m_joystickAxesCache[stick].m_count =
FRCNetworkCommunicationsLibrary.HALGetJoystickAxes(stick,
m_joystickAxesCache[stick].m_axes);
HAL.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes);
m_joystickPOVsCache[stick].m_count =
FRCNetworkCommunicationsLibrary.HALGetJoystickPOVs(stick,
m_joystickPOVsCache[stick].m_povs);
m_joystickButtonsCache[stick].m_buttons =
FRCNetworkCommunicationsLibrary.HALGetJoystickButtons(stick, m_buttonCountBuffer);
HAL.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs);
m_joystickButtonsCache[stick].m_buttons = HAL.getJoystickButtons(stick, m_buttonCountBuffer);
m_joystickButtonsCache[stick].m_count = m_buttonCountBuffer.get(0);
}
// lock joystick mutex to swap cache data
@@ -292,7 +286,7 @@ public class DriverStation implements RobotState.Interface {
if (stick < 0 || stick >= kJoystickPorts) {
throw new RuntimeException("Joystick index is out of range, should be 0-5");
}
if (axis < 0 || axis >= FRCNetworkCommunicationsLibrary.kMaxJoystickAxes) {
if (axis < 0 || axis >= HAL.kMaxJoystickAxes) {
throw new RuntimeException("Joystick axis is out of range");
}
@@ -338,7 +332,7 @@ public class DriverStation implements RobotState.Interface {
if (stick < 0 || stick >= kJoystickPorts) {
throw new RuntimeException("Joystick index is out of range, should be 0-5");
}
if (pov < 0 || pov >= FRCNetworkCommunicationsLibrary.kMaxJoystickPOVs) {
if (pov < 0 || pov >= HAL.kMaxJoystickPOVs) {
throw new RuntimeException("Joystick POV is out of range");
}
boolean error = false;
@@ -453,7 +447,7 @@ public class DriverStation implements RobotState.Interface {
if (1 > m_joystickButtons[stick].m_count && 1 > m_joystickAxes[stick].m_count) {
error = true;
retVal = false;
} else if (FRCNetworkCommunicationsLibrary.HALGetJoystickIsXbox((byte) stick) == 1) {
} else if (HAL.getJoystickIsXbox((byte) stick) == 1) {
retVal = true;
}
}
@@ -483,7 +477,7 @@ public class DriverStation implements RobotState.Interface {
error = true;
retVal = -1;
} else {
retVal = FRCNetworkCommunicationsLibrary.HALGetJoystickType((byte) stick);
retVal = HAL.getJoystickType((byte) stick);
}
}
if (error) {
@@ -512,7 +506,7 @@ public class DriverStation implements RobotState.Interface {
error = true;
retVal = "";
} else {
retVal = FRCNetworkCommunicationsLibrary.HALGetJoystickName((byte) stick);
retVal = HAL.getJoystickName((byte) stick);
}
}
if (error) {
@@ -528,7 +522,7 @@ public class DriverStation implements RobotState.Interface {
* @return True if the robot is enabled, false otherwise.
*/
public boolean isEnabled() {
HALControlWord controlWord = FRCNetworkCommunicationsLibrary.HALGetControlWord();
ControlWord controlWord = HAL.getControlWord();
return controlWord.getEnabled() && controlWord.getDSAttached();
}
@@ -548,7 +542,7 @@ public class DriverStation implements RobotState.Interface {
* @return True if autonomous mode should be enabled, false otherwise.
*/
public boolean isAutonomous() {
HALControlWord controlWord = FRCNetworkCommunicationsLibrary.HALGetControlWord();
ControlWord controlWord = HAL.getControlWord();
return controlWord.getAutonomous();
}
@@ -559,7 +553,7 @@ public class DriverStation implements RobotState.Interface {
* @return True if test mode should be enabled, false otherwise.
*/
public boolean isTest() {
HALControlWord controlWord = FRCNetworkCommunicationsLibrary.HALGetControlWord();
ControlWord controlWord = HAL.getControlWord();
return controlWord.getTest();
}
@@ -580,7 +574,7 @@ public class DriverStation implements RobotState.Interface {
* @return True if the FPGA outputs are enabled.
*/
public boolean isSysActive() {
return FRCNetworkCommunicationsLibrary.HALGetSystemActive();
return HAL.getSystemActive();
}
/**
@@ -589,7 +583,7 @@ public class DriverStation implements RobotState.Interface {
* @return True if the system is browned out
*/
public boolean isBrownedOut() {
return FRCNetworkCommunicationsLibrary.HALGetBrownedOut();
return HAL.getBrownedOut();
}
/**
@@ -612,8 +606,7 @@ public class DriverStation implements RobotState.Interface {
* @return the current alliance
*/
public Alliance getAlliance() {
HALAllianceStationID allianceStationID =
FRCNetworkCommunicationsLibrary.HALGetAllianceStation();
AllianceStationID allianceStationID = HAL.getAllianceStation();
if (allianceStationID == null) {
return Alliance.Invalid;
}
@@ -640,8 +633,7 @@ public class DriverStation implements RobotState.Interface {
* @return the location of the team's driver station controls: 1, 2, or 3
*/
public int getLocation() {
HALAllianceStationID allianceStationID =
FRCNetworkCommunicationsLibrary.HALGetAllianceStation();
AllianceStationID allianceStationID = HAL.getAllianceStation();
if (allianceStationID == null) {
return 0;
}
@@ -670,12 +662,12 @@ public class DriverStation implements RobotState.Interface {
* @return True if the robot is competing on a field being controlled by a Field Management System
*/
public boolean isFMSAttached() {
HALControlWord controlWord = FRCNetworkCommunicationsLibrary.HALGetControlWord();
ControlWord controlWord = HAL.getControlWord();
return controlWord.getFMSAttached();
}
public boolean isDSAttached() {
HALControlWord controlWord = FRCNetworkCommunicationsLibrary.HALGetControlWord();
ControlWord controlWord = HAL.getControlWord();
return controlWord.getDSAttached();
}
@@ -689,7 +681,7 @@ public class DriverStation implements RobotState.Interface {
* @return Time remaining in current match period (auto or teleop) in seconds
*/
public double getMatchTime() {
return FRCNetworkCommunicationsLibrary.HALGetMatchTime();
return HAL.getMatchTime();
}
/**
@@ -732,8 +724,7 @@ public class DriverStation implements RobotState.Interface {
haveLoc = true;
}
}
FRCNetworkCommunicationsLibrary.HALSendError(isError, code, false, error, locString,
printTrace ? traceString : "", true);
HAL.sendError(isError, code, false, error, locString, printTrace ? traceString : "", true);
}
/**

View File

@@ -10,9 +10,9 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.EncoderJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
@@ -79,7 +79,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW
m_pidSource = PIDSourceType.kDisplacement;
UsageReporting.report(tResourceType.kResourceType_Encoder, getFPGAIndex(), type.value);
HAL.report(tResourceType.kResourceType_Encoder, getFPGAIndex(), type.value);
LiveWindow.addSensor("Encoder", m_aSource.getChannel(), this);
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -52,9 +52,9 @@ public class GearTooth extends Counter {
super(channel);
enableDirectionSensing(directionSensitive);
if (directionSensitive) {
UsageReporting.report(tResourceType.kResourceType_GearTooth, channel, 0, "D");
HAL.report(tResourceType.kResourceType_GearTooth, channel, 0, "D");
} else {
UsageReporting.report(tResourceType.kResourceType_GearTooth, channel, 0);
HAL.report(tResourceType.kResourceType_GearTooth, channel, 0);
}
LiveWindow.addSensor("GearTooth", channel, this);
}

View File

@@ -9,8 +9,8 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.I2CJNI;
import edu.wpi.first.wpilibj.util.BoundaryException;
@@ -50,7 +50,7 @@ public class I2C extends SensorBase {
I2CJNI.i2CInitialize((byte) port.getValue());
UsageReporting.report(tResourceType.kResourceType_I2C, deviceAddress);
HAL.report(tResourceType.kResourceType_I2C, deviceAddress);
}
/**

View File

@@ -7,10 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -59,12 +58,13 @@ public class IterativeRobot extends RobotBase {
* Provide an alternate "main loop" via startCompetition().
*/
public void startCompetition() {
UsageReporting.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Iterative);
HAL.report(tResourceType.kResourceType_Framework,
tInstances.kFramework_Iterative);
robotInit();
// Tell the DS that the robot is ready to be enabled
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramStarting();
HAL.observeUserProgramStarting();
// loop forever, calling the appropriate mode-dependent function
LiveWindow.setEnabled(false);
@@ -83,7 +83,7 @@ public class IterativeRobot extends RobotBase {
m_testInitialized = false;
}
if (nextPeriodReady()) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramDisabled();
HAL.observeUserProgramDisabled();
disabledPeriodic();
}
} else if (isTest()) {
@@ -98,7 +98,7 @@ public class IterativeRobot extends RobotBase {
m_disabledInitialized = false;
}
if (nextPeriodReady()) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTest();
HAL.observeUserProgramTest();
testPeriodic();
}
} else if (isAutonomous()) {
@@ -116,7 +116,7 @@ public class IterativeRobot extends RobotBase {
m_disabledInitialized = false;
}
if (nextPeriodReady()) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramAutonomous();
HAL.observeUserProgramAutonomous();
autonomousPeriodic();
}
} else {
@@ -131,7 +131,7 @@ public class IterativeRobot extends RobotBase {
m_disabledInitialized = false;
}
if (nextPeriodReady()) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramTeleop();
HAL.observeUserProgramTeleop();
teleopPeriodic();
}
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -40,7 +40,7 @@ public class Jaguar extends PWMSpeedController {
setSpeed(0.0);
setZeroLatch();
UsageReporting.report(tResourceType.kResourceType_Jaguar, getChannel());
HAL.report(tResourceType.kResourceType_Jaguar, getChannel());
LiveWindow.addActuator("Jaguar", getChannel(), this);
}
}

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.HAL;
/**
* Handle input from standard Joysticks connected to the Driver Station. This class handles standard
@@ -157,7 +157,7 @@ public class Joystick extends GenericHID {
m_buttons[ButtonType.kTrigger.value] = kDefaultTriggerButton;
m_buttons[ButtonType.kTop.value] = kDefaultTopButton;
UsageReporting.report(tResourceType.kResourceType_Joystick, port);
HAL.report(tResourceType.kResourceType_Joystick, port);
}
/**
@@ -473,8 +473,7 @@ public class Joystick extends GenericHID {
} else {
m_rightRumble = (short) (value * 65535);
}
FRCNetworkCommunicationsLibrary.HALSetJoystickOutputs((byte) m_port, m_outputs, m_leftRumble,
m_rightRumble);
HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
}
/**
@@ -486,8 +485,7 @@ public class Joystick extends GenericHID {
public void setOutput(int outputNumber, boolean value) {
m_outputs = (m_outputs & ~(1 << (outputNumber - 1))) | ((value ? 1 : 0) << (outputNumber - 1));
FRCNetworkCommunicationsLibrary.HALSetJoystickOutputs((byte) m_port, m_outputs, m_leftRumble,
m_rightRumble);
HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
}
/**
@@ -497,7 +495,6 @@ public class Joystick extends GenericHID {
*/
public void setOutputs(int value) {
m_outputs = value;
FRCNetworkCommunicationsLibrary.HALSetJoystickOutputs((byte) m_port, m_outputs, m_leftRumble,
m_rightRumble);
HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
}
}

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.DIOJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.PWMJNI;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
@@ -78,7 +78,7 @@ public class PWM extends SensorBase implements LiveWindowSendable {
PWMJNI.setPWMEliminateDeadband(m_handle, false);
UsageReporting.report(tResourceType.kResourceType_PWM, channel);
HAL.report(tResourceType.kResourceType_PWM, channel);
}
/**

View File

@@ -9,8 +9,8 @@ package edu.wpi.first.wpilibj;
import java.util.Vector;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.networktables.NetworkTable;
import edu.wpi.first.wpilibj.tables.ITable;
import edu.wpi.first.wpilibj.tables.ITableListener;
@@ -77,7 +77,7 @@ public class Preferences {
private Preferences() {
m_table = NetworkTable.getTable(TABLE_NAME);
m_table.addTableListenerEx(m_listener, ITable.NOTIFY_NEW | ITable.NOTIFY_IMMEDIATE);
UsageReporting.report(tResourceType.kResourceType_Preferences, 0);
HAL.report(tResourceType.kResourceType_Preferences, 0);
}
/**

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.DIOJNI;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.RelayJNI;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -129,11 +129,11 @@ public class Relay extends SensorBase implements MotorSafety, LiveWindowSendable
int portHandle = RelayJNI.getPort((byte)m_channel);
if (m_direction == Direction.kBoth || m_direction == Direction.kForward) {
m_forwardHandle = RelayJNI.initializeRelayPort(portHandle, true);
UsageReporting.report(tResourceType.kResourceType_Relay, m_channel);
HAL.report(tResourceType.kResourceType_Relay, m_channel);
}
if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) {
m_reverseHandle = RelayJNI.initializeRelayPort(portHandle, false);
UsageReporting.report(tResourceType.kResourceType_Relay, m_channel + 128);
HAL.report(tResourceType.kResourceType_Relay, m_channel + 128);
}
m_safetyHelper = new MotorSafetyHelper(this);

View File

@@ -15,10 +15,9 @@ import java.util.Arrays;
import java.util.Enumeration;
import java.util.jar.Manifest;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.internal.HardwareHLUsageReporting;
import edu.wpi.first.wpilibj.internal.HardwareTimer;
import edu.wpi.first.wpilibj.networktables.NetworkTable;
@@ -161,7 +160,8 @@ public abstract class RobotBase {
* Common initialization for all robot programs.
*/
public static void initializeHardwareConfiguration() {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationReserve();
int rv = HAL.initialize(0);
assert rv == 1;
// Set some implementations so that the static methods work properly
Timer.SetImplementation(new HardwareTimer());
@@ -175,7 +175,7 @@ public abstract class RobotBase {
public static void main(String... args) {
initializeHardwareConfiguration();
UsageReporting.report(tResourceType.kResourceType_Language, tInstances.kLanguage_Java);
HAL.report(tResourceType.kResourceType_Language, tInstances.kLanguage_Java);
String robotName = "";
Enumeration<URL> resources = null;

View File

@@ -7,9 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import static java.util.Objects.requireNonNull;
@@ -191,7 +191,7 @@ public class RobotDrive implements MotorSafety {
final double rightOutput;
if (!kArcadeRatioCurve_Reported) {
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
tInstances.kRobotDrive_ArcadeRatioCurve);
kArcadeRatioCurve_Reported = true;
}
@@ -293,7 +293,7 @@ public class RobotDrive implements MotorSafety {
public void tankDrive(double leftValue, double rightValue, boolean squaredInputs) {
if (!kTank_Reported) {
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
tInstances.kRobotDrive_Tank);
kTank_Reported = true;
}
@@ -402,7 +402,7 @@ public class RobotDrive implements MotorSafety {
public void arcadeDrive(double moveValue, double rotateValue, boolean squaredInputs) {
// local variables to hold the computed PWM values for the motors
if (!kArcadeStandard_Reported) {
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
tInstances.kRobotDrive_ArcadeStandard);
kArcadeStandard_Reported = true;
}
@@ -480,7 +480,7 @@ public class RobotDrive implements MotorSafety {
@SuppressWarnings("ParameterName")
public void mecanumDrive_Cartesian(double x, double y, double rotation, double gyroAngle) {
if (!kMecanumCartesian_Reported) {
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
tInstances.kRobotDrive_MecanumCartesian);
kMecanumCartesian_Reported = true;
}
@@ -527,7 +527,7 @@ public class RobotDrive implements MotorSafety {
*/
public void mecanumDrive_Polar(double magnitude, double direction, double rotation) {
if (!kMecanumPolar_Reported) {
UsageReporting.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
tInstances.kRobotDrive_MecanumPolar);
kMecanumPolar_Reported = true;
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -36,7 +36,7 @@ public class SD540 extends PWMSpeedController {
setZeroLatch();
LiveWindow.addActuator("SD540", getChannel(), this);
UsageReporting.report(tResourceType.kResourceType_MindsensorsSD540, getChannel());
HAL.report(tResourceType.kResourceType_MindsensorsSD540, getChannel());
}
/**

View File

@@ -10,8 +10,8 @@ package edu.wpi.first.wpilibj;
import java.nio.ByteBuffer;
import java.nio.ByteOrder;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.SPIJNI;
/**
@@ -51,7 +51,7 @@ public class SPI extends SensorBase {
SPIJNI.spiInitialize(m_port);
UsageReporting.report(tResourceType.kResourceType_SPI, devices);
HAL.report(tResourceType.kResourceType_SPI, devices);
}
/**

View File

@@ -7,10 +7,9 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -111,12 +110,13 @@ public class SampleRobot extends RobotBase {
* for the robot to be enabled again.
*/
public void startCompetition() {
UsageReporting.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Sample);
HAL.report(tResourceType.kResourceType_Framework,
tInstances.kFramework_Simple);
robotInit();
// Tell the DS that the robot is ready to be enabled
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramStarting();
HAL.observeUserProgramStarting();
robotMain();
if (!m_robotMainOverridden) {

View File

@@ -10,8 +10,8 @@ package edu.wpi.first.wpilibj;
import java.io.UnsupportedEncodingException;
import java.nio.ByteBuffer;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.SerialPortJNI;
/**
@@ -207,7 +207,7 @@ public class SerialPort {
disableTermination();
UsageReporting.report(tResourceType.kResourceType_SerialPort, 0);
HAL.report(tResourceType.kResourceType_SerialPort, 0);
}
/**

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.tables.ITable;
import edu.wpi.first.wpilibj.tables.ITableListener;
@@ -42,7 +42,7 @@ public class Servo extends PWM {
setPeriodMultiplier(PeriodMultiplier.k4X);
LiveWindow.addActuator("Servo", getChannel(), this);
UsageReporting.report(tResourceType.kResourceType_Servo, getChannel());
HAL.report(tResourceType.kResourceType_Servo, getChannel());
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.hal.SolenoidJNI;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
@@ -54,7 +54,7 @@ public class Solenoid extends SolenoidBase implements LiveWindowSendable {
m_solenoidHandle = SolenoidJNI.initializeSolenoidPort(portHandle);
LiveWindow.addActuator("Solenoid", m_moduleNumber, m_channel, this);
UsageReporting.report(tResourceType.kResourceType_Solenoid, m_channel, m_moduleNumber);
HAL.report(tResourceType.kResourceType_Solenoid, m_channel, m_moduleNumber);
}
/**

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -36,7 +36,7 @@ public class Spark extends PWMSpeedController {
setZeroLatch();
LiveWindow.addActuator("Spark", getChannel(), this);
UsageReporting.report(tResourceType.kResourceType_RevSPARK, getChannel());
HAL.report(tResourceType.kResourceType_RevSPARK, getChannel());
}
/**

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -41,6 +41,6 @@ public class Talon extends PWMSpeedController {
setZeroLatch();
LiveWindow.addActuator("Talon", getChannel(), this);
UsageReporting.report(tResourceType.kResourceType_Talon, getChannel());
HAL.report(tResourceType.kResourceType_Talon, getChannel());
}
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -44,6 +44,6 @@ public class TalonSRX extends PWMSpeedController {
setZeroLatch();
LiveWindow.addActuator("TalonSRX", getChannel(), this);
UsageReporting.report(tResourceType.kResourceType_TalonSRX, getChannel());
HAL.report(tResourceType.kResourceType_TalonSRX, getChannel());
}
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable;
import edu.wpi.first.wpilibj.tables.ITable;
@@ -117,7 +117,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, LiveWindowSenda
setAutomaticMode(originalMode);
m_instances++;
UsageReporting.report(tResourceType.kResourceType_Ultrasonic, m_instances);
HAL.report(tResourceType.kResourceType_Ultrasonic, m_instances);
LiveWindow.addSensor("Ultrasonic", m_echoChannel.getChannel(), this);
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -43,6 +43,6 @@ public class Victor extends PWMSpeedController {
setZeroLatch();
LiveWindow.addActuator("Victor", getChannel(), this);
UsageReporting.report(tResourceType.kResourceType_Victor, getChannel());
HAL.report(tResourceType.kResourceType_Victor, getChannel());
}
}

View File

@@ -7,8 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -41,6 +41,6 @@ public class VictorSP extends PWMSpeedController {
setZeroLatch();
LiveWindow.addActuator("VictorSP", getChannel(), this);
UsageReporting.report(tResourceType.kResourceType_VictorSP, getChannel());
HAL.report(tResourceType.kResourceType_VictorSP, getChannel());
}
}

View File

@@ -927,11 +927,11 @@ public class CANJNI extends JNIWrapper {
public static final int CAN_IS_FRAME_11BIT = 0x40000000;
@SuppressWarnings("MethodName")
public static native void FRCNetworkCommunicationCANSessionMuxSendMessage(int messageID,
public static native void FRCNetCommCANSessionMuxSendMessage(int messageID,
ByteBuffer data,
int periodMs);
@SuppressWarnings("MethodName")
public static native ByteBuffer FRCNetworkCommunicationCANSessionMuxReceiveMessage(
public static native ByteBuffer FRCNetCommCANSessionMuxReceiveMessage(
IntBuffer messageID, int messageIDMask, ByteBuffer timeStamp);
}

View File

@@ -1,25 +0,0 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) FIRST 2016. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.communication;
public class UsageReporting {
public static void report(int resource, int instanceNumber, int context) {
report(resource, instanceNumber, context, "");
}
public static void report(int resource, int instanceNumber) {
report(resource, instanceNumber, 0, "");
}
public static void report(int resource, int instanceNumber, int context, String string) {
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationUsageReportingReport((byte) resource,
(byte) instanceNumber, (byte) context, string);
}
}

View File

@@ -5,8 +5,8 @@
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.communication;
package edu.wpi.first.wpilibj.hal;
public enum HALAllianceStationID {
public enum AllianceStationID {
Red1, Red2, Red3, Blue1, Blue2, Blue3
}

View File

@@ -5,12 +5,12 @@
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.communication;
package edu.wpi.first.wpilibj.hal;
/**
* A wrapper for the HALControlWord bitfield.
*/
public class HALControlWord {
public class ControlWord {
private final boolean m_enabled;
private final boolean m_autonomous;
private final boolean m_test;
@@ -18,8 +18,8 @@ public class HALControlWord {
private final boolean m_fmsAttached;
private final boolean m_dsAttached;
protected HALControlWord(boolean enabled, boolean autonomous, boolean test, boolean emergencyStop,
boolean fmsAttached, boolean dsAttached) {
protected ControlWord(boolean enabled, boolean autonomous, boolean test, boolean emergencyStop,
boolean fmsAttached, boolean dsAttached) {
m_enabled = enabled;
m_autonomous = autonomous;
m_test = test;
@@ -51,6 +51,4 @@ public class HALControlWord {
public boolean getDSAttached() {
return m_dsAttached;
}
}

View File

@@ -5,17 +5,15 @@
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.communication;
import java.nio.ByteBuffer;
package edu.wpi.first.wpilibj.hal;
import edu.wpi.first.wpilibj.hal.JNIWrapper;
/**
* JNI Wrapper for library <b>FRC_NetworkCommunications</b><br>.
* JNI wrapper for library <b>FRC_NetworkCommunication</b><br>.
*/
@SuppressWarnings("MethodName")
public class FRCNetworkCommunicationsLibrary extends JNIWrapper {
public class FRCNetComm extends JNIWrapper {
/**
* Module type from LoadOut.h
*/
@@ -35,18 +33,17 @@ public class FRCNetworkCommunicationsLibrary extends JNIWrapper {
int kTargetClass_Unknown = 0x00;
int kTargetClass_FRC1 = 0x10;
int kTargetClass_FRC2 = 0x20;
int kTargetClass_FRC2_Analog =
kTargetClass_FRC2 | FRCNetworkCommunicationsLibrary.tModuleType.kModuleType_Analog;
int kTargetClass_FRC2_Digital =
kTargetClass_FRC2 | FRCNetworkCommunicationsLibrary.tModuleType.kModuleType_Digital;
int kTargetClass_FRC2_Solenoid =
kTargetClass_FRC2 | FRCNetworkCommunicationsLibrary.tModuleType.kModuleType_Solenoid;
int kTargetClass_FRC3 = 0x30;
int kTargetClass_RoboRIO = 0x40;
int kTargetClass_FRC2_Analog = kTargetClass_FRC2 | tModuleType.kModuleType_Analog;
int kTargetClass_FRC2_Digital = kTargetClass_FRC2 | tModuleType.kModuleType_Digital;
int kTargetClass_FRC2_Solenoid = kTargetClass_FRC2 | tModuleType.kModuleType_Solenoid;
int kTargetClass_FamilyMask = 0xF0;
int kTargetClass_ModuleMask = 0x0F;
}
/**
* Resource types from UsageReporting.h
* Resource type from UsageReporting.h
*/
@SuppressWarnings("TypeName")
public interface tResourceType {
@@ -124,7 +121,7 @@ public class FRCNetworkCommunicationsLibrary extends JNIWrapper {
int kCANPlugin_2CAN = 2;
int kFramework_Iterative = 1;
int kFramework_Sample = 2;
int kFramework_Simple = 2;
int kFramework_CommandControl = 3;
int kRobotDrive_ArcadeStandard = 1;
@@ -157,100 +154,4 @@ public class FRCNetworkCommunicationsLibrary extends JNIWrapper {
int kSmartDashboard_Instance = 1;
}
/**
* Report the usage of a resource of interest. <br>
*
* <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 (max value 51). <br>
* @param instanceNumber an index that identifies the resource instance. <br>
* @param context an optional additional context number for some cases (such as module
* number). Set to 0 to omit. <br>
* @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.
*/
public static native int FRCNetworkCommunicationUsageReportingReport(byte resource,
byte instanceNumber,
byte context,
String feature);
public static native void setNewDataSem(long mutexId);
public static native void FRCNetworkCommunicationObserveUserProgramStarting();
public static native void FRCNetworkCommunicationObserveUserProgramDisabled();
public static native void FRCNetworkCommunicationObserveUserProgramAutonomous();
public static native void FRCNetworkCommunicationObserveUserProgramTeleop();
public static native void FRCNetworkCommunicationObserveUserProgramTest();
public static native void FRCNetworkCommunicationReserve();
private static native int NativeHALGetControlWord();
@SuppressWarnings("JavadocMethod")
public static HALControlWord HALGetControlWord() {
int word = NativeHALGetControlWord();
return new HALControlWord((word & 1) != 0, ((word >> 1) & 1) != 0, ((word >> 2) & 1) != 0,
((word >> 3) & 1) != 0, ((word >> 4) & 1) != 0, ((word >> 5) & 1) != 0);
}
private static native int NativeHALGetAllianceStation();
@SuppressWarnings("JavadocMethod")
public static HALAllianceStationID HALGetAllianceStation() {
switch (NativeHALGetAllianceStation()) {
case 0:
return HALAllianceStationID.Red1;
case 1:
return HALAllianceStationID.Red2;
case 2:
return HALAllianceStationID.Red3;
case 3:
return HALAllianceStationID.Blue1;
case 4:
return HALAllianceStationID.Blue2;
case 5:
return HALAllianceStationID.Blue3;
default:
return null;
}
}
public static int kMaxJoystickAxes = 12;
public static int kMaxJoystickPOVs = 12;
public static native byte HALGetJoystickAxes(byte joystickNum, float[] axesArray);
public static native byte HALGetJoystickPOVs(byte joystickNum, short[] povsArray);
public static native int HALGetJoystickButtons(byte joystickNum, ByteBuffer count);
public static native int HALSetJoystickOutputs(byte joystickNum, int outputs, short leftRumble,
short rightRumble);
public static native int HALGetJoystickIsXbox(byte joystickNum);
public static native int HALGetJoystickType(byte joystickNum);
public static native String HALGetJoystickName(byte joystickNum);
public static native int HALGetJoystickAxisType(byte joystickNum, byte axis);
public static native float HALGetMatchTime();
public static native boolean HALGetSystemActive();
public static native boolean HALGetBrownedOut();
public static native int HALSetErrorData(String error);
public static native int HALSendError(boolean isError, int errorCode, boolean isLVCode,
String details, String location, String callStack,
boolean printMsg);
}

View File

@@ -0,0 +1,119 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) FIRST 2016. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj.hal;
import java.nio.ByteBuffer;
import edu.wpi.first.wpilibj.hal.JNIWrapper;
/**
* JNI Wrapper for HAL<br>.
*/
@SuppressWarnings({"AbbreviationAsWordInName", "MethodName"})
public class HAL extends JNIWrapper {
public static native void setNewDataSem(long mutexId);
public static native int initialize(int mode);
public static native void observeUserProgramStarting();
public static native void observeUserProgramDisabled();
public static native void observeUserProgramAutonomous();
public static native void observeUserProgramTeleop();
public static native void observeUserProgramTest();
public static void report(int resource, int instanceNumber) {
report(resource, instanceNumber, 0, "");
}
public static void report(int resource, int instanceNumber, int context) {
report(resource, instanceNumber, context, "");
}
/**
* Report the usage of a resource of interest. <br>
*
* <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 (max value 51). <br>
* @param instanceNumber an index that identifies the resource instance. <br>
* @param context an optional additional context number for some cases (such as module
* number). Set to 0 to omit. <br>
* @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.
*/
public static native int report(int resource, int instanceNumber, int context, String feature);
private static native int nativeGetControlWord();
@SuppressWarnings("JavadocMethod")
public static ControlWord getControlWord() {
int word = nativeGetControlWord();
return new ControlWord((word & 1) != 0, ((word >> 1) & 1) != 0, ((word >> 2) & 1) != 0,
((word >> 3) & 1) != 0, ((word >> 4) & 1) != 0, ((word >> 5) & 1) != 0);
}
private static native int nativeGetAllianceStation();
@SuppressWarnings("JavadocMethod")
public static AllianceStationID getAllianceStation() {
switch (nativeGetAllianceStation()) {
case 0:
return AllianceStationID.Red1;
case 1:
return AllianceStationID.Red2;
case 2:
return AllianceStationID.Red3;
case 3:
return AllianceStationID.Blue1;
case 4:
return AllianceStationID.Blue2;
case 5:
return AllianceStationID.Blue3;
default:
return null;
}
}
public static int kMaxJoystickAxes = 12;
public static int kMaxJoystickPOVs = 12;
public static native short getJoystickAxes(byte joystickNum, float[] axesArray);
public static native short getJoystickPOVs(byte joystickNum, short[] povsArray);
public static native byte getJoystickButtons(byte joystickNum, ByteBuffer count);
public static native int setJoystickOutputs(byte joystickNum, int outputs, short leftRumble,
short rightRumble);
public static native int getJoystickIsXbox(byte joystickNum);
public static native int getJoystickType(byte joystickNum);
public static native String getJoystickName(byte joystickNum);
public static native int getJoystickAxisType(byte joystickNum, byte axis);
public static native float getMatchTime();
public static native boolean getSystemActive();
public static native boolean getBrownedOut();
public static native int setErrorData(String error);
public static native int sendError(boolean isError, int errorCode, boolean isLVCode,
String details, String location, String callStack,
boolean printMsg);
}

View File

@@ -8,23 +8,23 @@
package edu.wpi.first.wpilibj.internal;
import edu.wpi.first.wpilibj.HLUsageReporting;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tInstances;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary.tResourceType;
import edu.wpi.first.wpilibj.communication.UsageReporting;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tInstances;
import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType;
import edu.wpi.first.wpilibj.hal.HAL;
public class HardwareHLUsageReporting implements HLUsageReporting.Interface {
@Override
public void reportScheduler() {
UsageReporting.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler);
HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler);
}
@Override
public void reportPIDController(int num) {
UsageReporting.report(tResourceType.kResourceType_PIDController, num);
HAL.report(tResourceType.kResourceType_PIDController, num);
}
@Override
public void reportSmartDashboard() {
UsageReporting.report(tResourceType.kResourceType_SmartDashboard, 0);
HAL.report(tResourceType.kResourceType_SmartDashboard, 0);
}
}

View File

@@ -19,7 +19,7 @@ import java.util.logging.Logger;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.communication.FRCNetworkCommunicationsLibrary;
import edu.wpi.first.wpilibj.hal.HAL;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
/**
@@ -44,7 +44,7 @@ public abstract class AbstractComsSetup {
if (!initialized) {
// Set some implementations so that the static methods work properly
RobotBase.initializeHardwareConfiguration();
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationObserveUserProgramStarting();
HAL.observeUserProgramStarting();
LiveWindow.setEnabled(false);
TestBench.out().println("Started coms");