From 95dd20a151c1d4e7b33f4aacb1578897569ca979 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 24 Sep 2021 16:04:02 -0700 Subject: [PATCH] [build] Enable spotbugs (#3601) Benign spotbugs warnings were suppressed, and all others were fixed. Bug descriptions are documented here: https://spotbugs.readthedocs.io/en/stable/bugDescriptions.html Co-authored-by: Austin Shalit --- .github/workflows/lint-format.yml | 30 ++--- README.md | 4 +- azure-pipelines-testbench.yaml | 2 +- build.gradle | 49 +------- .../src/main/java/edu/wpi/Main.java | 6 +- .../edu/wpi/first/cscore/ImageSource.java | 13 -- .../edu/wpi/first/cscore/UsbCameraTest.java | 2 +- .../java/edu/wpi/first/hal/can/CANJNI.java | 2 +- hal/src/main/native/cpp/jni/CANJNI.cpp | 4 +- shared/java/javacommon.gradle | 4 - shared/java/javastyle.gradle | 54 +++++++++ ...ssions.xml => checkstyle-suppressions.xml} | 0 styleguide/checkstyle.xml | 3 +- styleguide/spotbugs-exclude.xml | 81 +++++++++++++ .../command/CommandGroupErrorTest.java | 6 +- .../wpilibj2/command/CommandTestBase.java | 8 +- .../java/edu/wpi/first/wpilibj/PIDBase.java | 19 ++- .../wpilibj/command/AbstractCommandTest.java | 2 +- .../command/ConditionalCommandTest.java | 1 - .../native/cpp/smartdashboard/Field2d.cpp | 2 +- .../native/cpp/smartdashboard/Mechanism2d.cpp | 7 +- .../smartdashboard/MechanismLigament2d.cpp | 1 + .../cpp/smartdashboard/MechanismRoot2d.cpp | 2 + .../first/wpilibj/DigitalGlitchFilter.java | 11 +- .../edu/wpi/first/wpilibj/DriverStation.java | 14 ++- .../java/edu/wpi/first/wpilibj/RobotBase.java | 12 +- .../wpi/first/wpilibj/RobotController.java | 2 +- .../edu/wpi/first/wpilibj/TimedRobot.java | 15 ++- .../java/edu/wpi/first/wpilibj/Watchdog.java | 21 ++-- .../first/wpilibj/smartdashboard/Field2d.java | 4 +- .../wpilibj/smartdashboard/Mechanism2d.java | 6 +- .../smartdashboard/MechanismLigament2d.java | 2 +- .../smartdashboard/MechanismRoot2d.java | 4 +- .../wpi/first/wpilibj/PreferencesTest.java | 2 +- .../edu/wpi/first/wpilibj/TimedRobotTest.java | 2 +- .../wpi/first/wpilibj/can/CANStatusTest.java | 2 +- .../first/wpilibj/PreferencesTestDefault.ini | 3 +- .../first/wpilibj/examples/pacgoat/Robot.java | 10 +- .../templates/oldcommandbased/Robot.java | 2 +- wpilibjIntegrationTests/build.gradle | 2 +- .../java/edu/wpi/first/wpilibj/PIDTest.java | 2 +- .../wpi/first/wpilibj/can/CANStatusTest.java | 2 +- .../fixtures/AnalogCrossConnectFixture.java | 9 +- .../fixtures/DIOCrossConnectFixture.java | 10 +- .../wpilibj/fixtures/FakeCounterFixture.java | 10 +- .../wpilibj/fixtures/FakeEncoderFixture.java | 10 +- .../first/wpilibj/fixtures/ITestFixture.java | 12 +- .../wpilibj/fixtures/MotorEncoderFixture.java | 49 ++------ .../fixtures/RelayCrossConnectFixture.java | 9 +- .../first/wpilibj/fixtures/SampleFixture.java | 9 +- .../fixtures/TiltPanCameraFixture.java | 11 +- .../mockhardware/FakeCounterSource.java | 2 +- .../mockhardware/FakeEncoderSource.java | 2 +- .../first/wpilibj/test/AbstractComsSetup.java | 2 +- .../first/wpilibj/test/AbstractTestSuite.java | 2 +- .../wpilibj/test/AbstractTestSuiteTest.java | 2 +- ...nitLanucher.java => AntJunitLauncher.java} | 2 +- .../edu/wpi/first/wpilibj/test/TestSuite.java | 9 +- .../edu/wpi/first/math/StateSpaceUtil.java | 4 +- .../wpi/first/math/filter/MedianFilter.java | 4 +- .../math/kinematics/SwerveModuleState.java | 22 +++- .../native/include/frc/filter/MedianFilter.h | 4 +- ...olAffinePlantInversionFeedforwardTest.java | 19 +-- .../HolonomicDriveControllerTest.java | 3 +- .../LinearQuadraticRegulatorTest.java | 35 +----- .../math/controller/LinearSystemLoopTest.java | 26 ---- .../estimator/ExtendedKalmanFilterTest.java | 29 ----- .../math/estimator/KalmanFilterTest.java | 56 --------- .../estimator/UnscentedKalmanFilterTest.java | 113 ------------------ .../HolonomicDriveControllerTest.cpp | 4 +- .../wpi/first/util/CombinedRuntimeLoader.java | 6 +- .../edu/wpi/first/util/RuntimeDetector.java | 3 + .../edu/wpi/first/util/RuntimeLoader.java | 16 ++- 73 files changed, 356 insertions(+), 558 deletions(-) rename styleguide/{suppressions.xml => checkstyle-suppressions.xml} (100%) create mode 100644 styleguide/spotbugs-exclude.xml rename wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/{AntJunitLanucher.java => AntJunitLauncher.java} (98%) diff --git a/.github/workflows/lint-format.yml b/.github/workflows/lint-format.yml index 88c58d6fb6..a7aafe8f9c 100644 --- a/.github/workflows/lint-format.yml +++ b/.github/workflows/lint-format.yml @@ -69,29 +69,8 @@ jobs: run: wpiformat -list-changed-files - name: Run clang-tidy run: wpiformat -clang 12 -no-format -tidy-changed -compile-commands=build/compile_commands/linuxx86-64 -vv - spotless: - name: "Spotless" - runs-on: ubuntu-latest - container: wpilib/ubuntu-base:18.04 - steps: - - uses: actions/checkout@v2 - with: - fetch-depth: 0 - - name: Run spotless - run: ./gradlew spotlessCheck - - name: Apply Spotless - run: ./gradlew :spotlessApply - if: ${{ failure() }} - - name: Generate diff - run: git diff HEAD > spotless-fixes.patch - if: ${{ failure() }} - - uses: actions/upload-artifact@v2 - with: - name: spotless fixes - path: spotless-fixes.patch - if: ${{ failure() }} javaformat: - name: "Checkstyle and PMD" + name: "Java format" runs-on: ubuntu-latest container: wpilib/ubuntu-base:18.04 steps: @@ -99,4 +78,9 @@ jobs: with: fetch-depth: 0 - name: Run Java format - run: ./gradlew javaFormat + run: ./gradlew javaFormat spotbugsMain spotbugsTest spotbugsDev + - name: Check output + run: git --no-pager diff --exit-code HEAD + - name: Generate diff + run: git diff HEAD > javaformat-fixes.patch + if: ${{ failure() }} diff --git a/README.md b/README.md index b783674311..1ddac77284 100644 --- a/README.md +++ b/README.md @@ -120,7 +120,9 @@ wpiformat can be executed anywhere in the repository via `py -3 -m wpiformat` on #### Java Code Quality Tools -The Java code quality tools Checkstyle and PMD can be run via `./gradlew javaFormat`. Spotless can be run via `./gradlew spotlessCheck` to preview changes, and via `./gradlew spotlessApply` to immediately apply changes. These tools will all be run automatically by the build task. To disable this behavior, pass the `-PskipJavaFormat` flag. +The Java code quality tools Checkstyle, PMD, and Spotless can be run via `./gradlew javaFormat`. SpotBugs can be run via the `spotbugsMain`, `spotbugsTest`, and `spotbugsDev` tasks. These tools will all be run automatically by the `build` task. To disable this behavior, pass the `-PskipJavaFormat` flag. + +If you only want to run the Java autoformatter, run `./gradlew spotlessApply`. ### CMake diff --git a/azure-pipelines-testbench.yaml b/azure-pipelines-testbench.yaml index e6dd9fd160..d1c9347486 100644 --- a/azure-pipelines-testbench.yaml +++ b/azure-pipelines-testbench.yaml @@ -29,7 +29,7 @@ stages: publishJUnitResults: false testResultsFiles: "**/TEST-*.xml" tasks: "copyWpilibJIntegrationTestJarToOutput copyWpilibCTestLibrariesToOutput" - options: "-Ponlylinuxathena -PbuildServer" + options: "-Ponlylinuxathena -PbuildServer -PskipJavaFormat" - task: PublishPipelineArtifact@0 inputs: diff --git a/build.gradle b/build.gradle index b634785f3d..19ee6a8042 100644 --- a/build.gradle +++ b/build.gradle @@ -20,7 +20,8 @@ plugins { id 'visual-studio' id 'net.ltgt.errorprone' version '1.1.1' apply false id 'com.github.johnrengelman.shadow' version '5.2.0' apply false - id 'com.diffplug.spotless' version '5.5.0' + id 'com.diffplug.spotless' version '5.5.0' apply false + id 'com.github.spotbugs' version '5.0.0-beta.1' apply false } wpilibVersioning.buildServerMode = project.hasProperty('buildServer') @@ -145,52 +146,6 @@ ext.getCurrentArch = { return NativePlatforms.desktop } -spotless { - if (project.hasProperty('skipJavaFormat')) { - enforceCheck false - } - java { - target fileTree('.') { - include '**/*.java' - exclude '**/build/**', '**/build-*/**' - } - toggleOffOn() - googleJavaFormat() - removeUnusedImports() - trimTrailingWhitespace() - endWithNewline() - } - groovyGradle { - target fileTree('.') { - include '**/*.gradle' - exclude '**/build/**', '**/build-*/**' - } - greclipse() - indentWithSpaces(4) - trimTrailingWhitespace() - endWithNewline() - } - format 'xml', { - target fileTree('.') { - include '**/*.xml' - exclude '**/build/**', '**/build-*/**' - } - eclipseWtp('xml') - trimTrailingWhitespace() - indentWithSpaces(2) - endWithNewline() - } - format 'misc', { - target fileTree('.') { - include '**/*.md', '**/.gitignore' - exclude '**/build/**', '**/build-*/**' - } - trimTrailingWhitespace() - indentWithSpaces(2) - endWithNewline() - } -} - wrapper { gradleVersion = '7.1.1' } diff --git a/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java b/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java index 4bdd626dad..f6f91c1baa 100644 --- a/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java +++ b/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java @@ -56,9 +56,9 @@ public final class Main { public JsonObject config; } - public static int team; - public static boolean server; - public static List cameras = new ArrayList<>(); + static int team; + static boolean server; + static List cameras = new ArrayList<>(); private Main() {} diff --git a/cscore/src/main/java/edu/wpi/first/cscore/ImageSource.java b/cscore/src/main/java/edu/wpi/first/cscore/ImageSource.java index 4ef05fd1bd..6bebed811a 100644 --- a/cscore/src/main/java/edu/wpi/first/cscore/ImageSource.java +++ b/cscore/src/main/java/edu/wpi/first/cscore/ImageSource.java @@ -133,17 +133,4 @@ public abstract class ImageSource extends VideoSource { public void setEnumPropertyChoices(VideoProperty property, String[] choices) { CameraServerJNI.setSourceEnumPropertyChoices(m_handle, property.m_handle, choices); } - - /** - * Configure enum property choices. - * - * @param property Property - * @param choices Choices - * @deprecated Use {@code setEnumPropertyChoices} instead. - */ - @Deprecated - @SuppressWarnings("MethodName") - public void SetEnumPropertyChoices(VideoProperty property, String[] choices) { - setEnumPropertyChoices(property, choices); - } } diff --git a/cscore/src/test/java/edu/wpi/first/cscore/UsbCameraTest.java b/cscore/src/test/java/edu/wpi/first/cscore/UsbCameraTest.java index 8a790fa788..f0a679f6a8 100644 --- a/cscore/src/test/java/edu/wpi/first/cscore/UsbCameraTest.java +++ b/cscore/src/test/java/edu/wpi/first/cscore/UsbCameraTest.java @@ -21,7 +21,7 @@ import org.junit.jupiter.api.condition.OS; class UsbCameraTest { @Nested @EnabledOnOs(OS.LINUX) - class ConnectVerbose { + static class ConnectVerbose { @Test void setConnectVerboseEnabledTest() { try (UsbCamera camera = new UsbCamera("Nonexistant Camera", getNonexistentCameraDev())) { diff --git a/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java b/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java index 6281543df9..b4f344fd6f 100644 --- a/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java @@ -26,5 +26,5 @@ public class CANJNI extends JNIWrapper { IntBuffer messageID, int messageIDMask, ByteBuffer timeStamp); @SuppressWarnings("MethodName") - public static native void GetCANStatus(CANStatus status); + public static native void getCANStatus(CANStatus status); } diff --git a/hal/src/main/native/cpp/jni/CANJNI.cpp b/hal/src/main/native/cpp/jni/CANJNI.cpp index 3eeedc6425..968f656634 100644 --- a/hal/src/main/native/cpp/jni/CANJNI.cpp +++ b/hal/src/main/native/cpp/jni/CANJNI.cpp @@ -69,11 +69,11 @@ Java_edu_wpi_first_hal_can_CANJNI_FRCNetCommCANSessionMuxReceiveMessage /* * Class: edu_wpi_first_hal_can_CANJNI - * Method: GetCANStatus + * Method: getCANStatus * Signature: (Ljava/lang/Object;)V */ JNIEXPORT void JNICALL -Java_edu_wpi_first_hal_can_CANJNI_GetCANStatus +Java_edu_wpi_first_hal_can_CANJNI_getCANStatus (JNIEnv* env, jclass, jobject canStatus) { float percentBusUtilization = 0; diff --git a/shared/java/javacommon.gradle b/shared/java/javacommon.gradle index 43e13d3eac..2eb14384eb 100644 --- a/shared/java/javacommon.gradle +++ b/shared/java/javacommon.gradle @@ -1,6 +1,5 @@ apply plugin: 'maven-publish' apply plugin: 'java-library' -//apply plugin: 'net.ltgt.errorprone' apply plugin: 'jacoco' def baseArtifactId = project.baseId @@ -110,9 +109,6 @@ dependencies { testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.4.2' devImplementation sourceSets.main.output - - //errorprone 'com.google.errorprone:error_prone_core:2.3.2-SNAPSHOT' - //errorproneJavac 'com.google.errorprone:error_prone_core:2.3.1' } task run(type: JavaExec) { diff --git a/shared/java/javastyle.gradle b/shared/java/javastyle.gradle index 2a65dc565b..281eed3d5f 100644 --- a/shared/java/javastyle.gradle +++ b/shared/java/javastyle.gradle @@ -16,9 +16,63 @@ if (!project.hasProperty('skipJavaFormat')) { ruleSetFiles = files(new File(rootDir, "styleguide/pmd-ruleset.xml")) ruleSets = [] } + + apply plugin: 'com.diffplug.spotless' + + spotless { + java { + target fileTree('.') { + include '**/*.java' + exclude '**/build/**', '**/build-*/**' + } + toggleOffOn() + googleJavaFormat() + removeUnusedImports() + trimTrailingWhitespace() + endWithNewline() + } + groovyGradle { + target fileTree('.') { + include '**/*.gradle' + exclude '**/build/**', '**/build-*/**' + } + greclipse() + indentWithSpaces(4) + trimTrailingWhitespace() + endWithNewline() + } + format 'xml', { + target fileTree('.') { + include '**/*.xml' + exclude '**/build/**', '**/build-*/**' + } + eclipseWtp('xml') + trimTrailingWhitespace() + indentWithSpaces(2) + endWithNewline() + } + format 'misc', { + target fileTree('.') { + include '**/*.md', '**/.gitignore' + exclude '**/build/**', '**/build-*/**' + } + trimTrailingWhitespace() + indentWithSpaces(2) + endWithNewline() + } + } + + apply plugin: 'com.github.spotbugs' + + spotbugs { + ignoreFailures = false + effort = 'max' + excludeFilter = file("${project.rootDir}/styleguide/spotbugs-exclude.xml") + } } task javaFormat { dependsOn(tasks.withType(Checkstyle)) dependsOn(tasks.withType(Pmd)) } +javaFormat.dependsOn 'spotlessApply' diff --git a/styleguide/suppressions.xml b/styleguide/checkstyle-suppressions.xml similarity index 100% rename from styleguide/suppressions.xml rename to styleguide/checkstyle-suppressions.xml diff --git a/styleguide/checkstyle.xml b/styleguide/checkstyle.xml index f3ec47d910..3796fe341f 100644 --- a/styleguide/checkstyle.xml +++ b/styleguide/checkstyle.xml @@ -12,7 +12,8 @@ module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN" - + diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml new file mode 100644 index 0000000000..feec066961 --- /dev/null +++ b/styleguide/spotbugs-exclude.xml @@ -0,0 +1,81 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java index da784736fc..8da92c751c 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java @@ -17,8 +17,7 @@ class CommandGroupErrorTest extends CommandTestBase { MockCommandHolder command2Holder = new MockCommandHolder(true); Command command2 = command2Holder.getMock(); - @SuppressWarnings("PMD.UnusedLocalVariable") - Command group = new ParallelCommandGroup(command1, command2); + new ParallelCommandGroup(command1, command2); assertThrows( IllegalArgumentException.class, () -> new ParallelCommandGroup(command1, command2)); } @@ -31,8 +30,7 @@ class CommandGroupErrorTest extends CommandTestBase { MockCommandHolder command2Holder = new MockCommandHolder(true); Command command2 = command2Holder.getMock(); - @SuppressWarnings("PMD.UnusedLocalVariable") - Command group = new ParallelCommandGroup(command1, command2); + new ParallelCommandGroup(command1, command2); assertThrows(IllegalArgumentException.class, () -> scheduler.schedule(command1)); } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java index 8ba1cee700..88190ed41a 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java @@ -41,9 +41,9 @@ public abstract class CommandTestBase { } } - public class TestSubsystem extends SubsystemBase {} + public static class TestSubsystem extends SubsystemBase {} - public class MockCommandHolder { + public static class MockCommandHolder { private final Command m_mockCommand = mock(Command.class); public MockCommandHolder(boolean runWhenDisabled, Subsystem... requirements) { @@ -61,7 +61,7 @@ public abstract class CommandTestBase { } } - public class Counter { + public static class Counter { public int m_counter; public void increment() { @@ -69,7 +69,7 @@ public abstract class CommandTestBase { } } - public class ConditionHolder { + public static class ConditionHolder { private boolean m_condition; public void setCondition(boolean condition) { diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java index 75a6d08aff..505801a57f 100644 --- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java +++ b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java @@ -267,21 +267,18 @@ public class PIDBase implements PIDInterface, PIDOutput, Sendable, AutoCloseable // Ensures m_enabled check and pidWrite() call occur atomically m_pidWriteMutex.lock(); + m_thisMutex.lock(); try { - m_thisMutex.lock(); - try { - if (m_enabled) { - // Don't block other PIDController operations on pidWrite() - m_thisMutex.unlock(); + if (m_enabled) { + // Don't block other PIDController operations on pidWrite() + m_thisMutex.unlock(); - m_pidOutput.pidWrite(result); - } - } finally { - if (m_thisMutex.isHeldByCurrentThread()) { - m_thisMutex.unlock(); - } + m_pidOutput.pidWrite(result); } } finally { + if (!m_enabled) { + m_thisMutex.unlock(); + } m_pidWriteMutex.unlock(); } diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java index 5c0977fb49..d305595230 100644 --- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java +++ b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java @@ -18,7 +18,7 @@ public abstract class AbstractCommandTest { Scheduler.getInstance().enable(); } - public class ASubsystem extends Subsystem { + public static class ASubsystem extends Subsystem { Command m_command; @Override diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java index 90e6d4d4b9..97d33774d0 100644 --- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java +++ b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java @@ -17,7 +17,6 @@ class ConditionalCommandTest extends AbstractCommandTest { MockCommand m_onTrue; MockCommand m_onFalse; MockSubsystem m_subsys; - Boolean m_condition; @BeforeEach void initCommands() { diff --git a/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp index e3080fe6eb..2915a124fc 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp @@ -69,9 +69,9 @@ FieldObject2d* Field2d::GetRobotObject() { void Field2d::InitSendable(nt::NTSendableBuilder& builder) { builder.SetSmartDashboardType("Field2d"); - m_table = builder.GetTable(); std::scoped_lock lock(m_mutex); + m_table = builder.GetTable(); for (auto&& obj : m_objects) { std::scoped_lock lock2(obj->m_mutex); obj->m_entry = m_table->GetEntry(obj->m_name); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp index 4dcdffaa13..bfa827a5b7 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp @@ -43,12 +43,11 @@ void Mechanism2d::SetBackgroundColor(const Color8Bit& color) { void Mechanism2d::InitSendable(nt::NTSendableBuilder& builder) { builder.SetSmartDashboardType("Mechanism2d"); - m_table = builder.GetTable(); - - m_table->GetEntry(kDims).SetDoubleArray({m_width, m_height}); - m_table->GetEntry(kBackgroundColor).SetString(m_color); std::scoped_lock lock(m_mutex); + m_table = builder.GetTable(); + m_table->GetEntry(kDims).SetDoubleArray({m_width, m_height}); + m_table->GetEntry(kBackgroundColor).SetString(m_color); for (const auto& entry : m_roots) { const auto& root = entry.getValue().get(); root->Update(m_table->GetSubTable(entry.getKey())); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp index 870cfb51f4..c46b8e12d3 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp @@ -21,6 +21,7 @@ MechanismLigament2d::MechanismLigament2d(std::string_view name, double length, void MechanismLigament2d::UpdateEntries( std::shared_ptr table) { + std::scoped_lock lock(m_mutex); table->GetEntry(".type").SetString("line"); m_colorEntry = table->GetEntry("color"); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp index 637b24b0f2..07d15f0118 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp @@ -20,12 +20,14 @@ void MechanismRoot2d::SetPosition(double x, double y) { } void MechanismRoot2d::UpdateEntries(std::shared_ptr table) { + std::scoped_lock lock(m_mutex); m_xEntry = table->GetEntry("x"); m_yEntry = table->GetEntry("y"); Flush(); } inline void MechanismRoot2d::Flush() { + std::scoped_lock lock(m_mutex); if (m_xEntry) { m_xEntry.SetDouble(m_x); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java index 7e12a8f03e..abcc67b967 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java @@ -21,7 +21,8 @@ import java.util.concurrent.locks.ReentrantLock; public class DigitalGlitchFilter implements Sendable, AutoCloseable { /** Configures the Digital Glitch Filter to its default settings. */ public DigitalGlitchFilter() { - synchronized (m_mutex) { + m_mutex.lock(); + try { int index = 0; while (m_filterAllocated[index] && index < m_filterAllocated.length) { index++; @@ -32,6 +33,8 @@ public class DigitalGlitchFilter implements Sendable, AutoCloseable { HAL.report(tResourceType.kResourceType_DigitalGlitchFilter, m_channelIndex + 1, 0); SendableRegistry.addLW(this, "DigitalGlitchFilter", index); } + } finally { + m_mutex.unlock(); } } @@ -39,9 +42,13 @@ public class DigitalGlitchFilter implements Sendable, AutoCloseable { public void close() { SendableRegistry.remove(this); if (m_channelIndex >= 0) { - synchronized (m_mutex) { + m_mutex.lock(); + try { m_filterAllocated[m_channelIndex] = false; + } finally { + m_mutex.unlock(); } + m_channelIndex = -1; } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java index afd2393185..c450c5e949 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java @@ -188,12 +188,15 @@ public class DriverStation { int currentReplayNumber; int currentMatchType; int currentControlWord; - synchronized (DriverStation.m_cacheDataMutex) { + m_cacheDataMutex.lock(); + try { currentEventName = DriverStation.m_matchInfo.eventName; currentGameSpecificMessage = DriverStation.m_matchInfo.gameSpecificMessage; currentMatchNumber = DriverStation.m_matchInfo.matchNumber; currentReplayNumber = DriverStation.m_matchInfo.replayNumber; currentMatchType = DriverStation.m_matchInfo.matchType; + } finally { + m_cacheDataMutex.unlock(); } currentControlWord = HAL.nativeGetControlWord(); @@ -1178,9 +1181,12 @@ public class DriverStation { /** Forces waitForData() to return immediately. */ public static void wakeupWaitForData() { m_waitForDataMutex.lock(); - m_waitForDataCount++; - m_waitForDataCond.signalAll(); - m_waitForDataMutex.unlock(); + try { + m_waitForDataCount++; + m_waitForDataCond.signalAll(); + } finally { + m_waitForDataMutex.unlock(); + } } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java index fe48b28b22..8d1fb07b05 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -348,20 +348,20 @@ public abstract class RobotBase implements AutoCloseable { m_runMutex.unlock(); if (isReal()) { + final File file = new File("/tmp/frc_versions/FRC_Lib_Version.ini"); try { - final File file = new File("/tmp/frc_versions/FRC_Lib_Version.ini"); - - if (file.exists()) { - file.delete(); + if (file.exists() && !file.delete()) { + throw new IOException("Failed to delete FRC_Lib_Version.ini"); } - file.createNewFile(); + if (!file.createNewFile()) { + throw new IOException("Failed to create new FRC_Lib_Version.ini"); + } try (OutputStream output = Files.newOutputStream(file.toPath())) { output.write("Java ".getBytes(StandardCharsets.UTF_8)); output.write(WPILibVersion.Version.getBytes(StandardCharsets.UTF_8)); } - } catch (IOException ex) { DriverStation.reportError( "Could not write FRC_Lib_Version.ini: " + ex.toString(), ex.getStackTrace()); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java index 31db69bada..59fd507c3f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java @@ -220,7 +220,7 @@ public final class RobotController { */ public static CANStatus getCANStatus() { CANStatus status = new CANStatus(); - CANJNI.GetCANStatus(status); + CANJNI.getCANStatus(status); return status; } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java index 04b95f99f0..dda62d241f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java @@ -19,7 +19,7 @@ import java.util.PriorityQueue; */ public class TimedRobot extends IterativeRobotBase { @SuppressWarnings("MemberName") - class Callback implements Comparable { + static class Callback implements Comparable { public Runnable func; public double period; public double expirationTime; @@ -43,6 +43,19 @@ public class TimedRobot extends IterativeRobotBase { + this.period; } + @Override + public boolean equals(Object rhs) { + if (rhs instanceof Callback) { + return Double.compare(expirationTime, ((Callback) rhs).expirationTime) == 0; + } + return false; + } + + @Override + public int hashCode() { + return Double.hashCode(expirationTime); + } + @Override public int compareTo(Callback rhs) { // Elements with sooner expiration times are sorted as lesser. The head of diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java index 044324f414..22581a56ec 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java @@ -60,20 +60,12 @@ public class Watchdog implements Closeable, Comparable { disable(); } - @Override - public int compareTo(Watchdog rhs) { - // Elements with sooner expiration times are sorted as lesser. The head of - // Java's PriorityQueue is the least element. - return Double.compare(m_expirationTimeSeconds, rhs.m_expirationTimeSeconds); - } - @Override public boolean equals(Object obj) { - if (!(obj instanceof Watchdog)) { - return false; + if (obj instanceof Watchdog) { + return Double.compare(m_expirationTimeSeconds, ((Watchdog) obj).m_expirationTimeSeconds) == 0; } - Watchdog oth = (Watchdog) obj; - return oth.m_expirationTimeSeconds == m_expirationTimeSeconds; + return false; } @Override @@ -81,6 +73,13 @@ public class Watchdog implements Closeable, Comparable { return Double.hashCode(m_expirationTimeSeconds); } + @Override + public int compareTo(Watchdog rhs) { + // Elements with sooner expiration times are sorted as lesser. The head of + // Java's PriorityQueue is the least element. + return Double.compare(m_expirationTimeSeconds, rhs.m_expirationTimeSeconds); + } + /** * Returns the time in seconds since the watchdog was last fed. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java index f83ee07fcd..b76f0560fb 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java @@ -76,7 +76,7 @@ public class Field2d implements NTSendable { */ public synchronized FieldObject2d getObject(String name) { for (FieldObject2d obj : m_objects) { - if (obj.m_name == name) { + if (obj.m_name.equals(name)) { return obj; } } @@ -102,9 +102,9 @@ public class Field2d implements NTSendable { @Override public void initSendable(NTSendableBuilder builder) { builder.setSmartDashboardType("Field2d"); - m_table = builder.getTable(); synchronized (this) { + m_table = builder.getTable(); for (FieldObject2d obj : m_objects) { synchronized (obj) { obj.m_entry = m_table.getEntry(obj.m_name); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java index aa600fe7b1..89679442f0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Mechanism2d.java @@ -97,10 +97,10 @@ public final class Mechanism2d implements NTSendable { @Override public void initSendable(NTSendableBuilder builder) { builder.setSmartDashboardType("Mechanism2d"); - m_table = builder.getTable(); - m_table.getEntry("dims").setDoubleArray(m_dims); - m_table.getEntry(kBackgroundColor).setString(m_color); synchronized (this) { + m_table = builder.getTable(); + m_table.getEntry("dims").setDoubleArray(m_dims); + m_table.getEntry(kBackgroundColor).setString(m_color); for (Entry entry : m_roots.entrySet()) { String name = entry.getKey(); MechanismRoot2d root = entry.getValue(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java index d6cd2b46de..8579936e33 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java @@ -128,7 +128,7 @@ public class MechanismLigament2d extends MechanismObject2d { } @Override - protected void updateEntries(NetworkTable table) { + protected synchronized void updateEntries(NetworkTable table) { table.getEntry(".type").setString("line"); m_angleEntry = table.getEntry("angle"); m_lengthEntry = table.getEntry("length"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java index 7c6de65852..39f4515493 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java @@ -72,7 +72,7 @@ public final class MechanismRoot2d { m_y = y; } - void update(NetworkTable table) { + synchronized void update(NetworkTable table) { m_table = table; m_xEntry = m_table.getEntry("x"); m_yEntry = m_table.getEntry("y"); @@ -86,7 +86,7 @@ public final class MechanismRoot2d { return m_name; } - private void flush() { + private synchronized void flush() { if (m_xEntry != null) { m_xEntry.setDouble(m_x); } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java index 2dd400b5e4..2603d5b382 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/PreferencesTest.java @@ -95,7 +95,7 @@ class PreferencesTest { () -> assertEquals(0.2, m_prefs.getDouble("checkedValueDouble", 0), 1e-6), () -> assertEquals("Hello. How are you?", m_prefs.getString("checkedValueString", "")), () -> assertEquals(2, m_prefs.getInt("checkedValueInt", 0)), - () -> assertEquals(3.14, m_prefs.getFloat("checkedValueFloat", 0), 1e-6), + () -> assertEquals(3.4, m_prefs.getFloat("checkedValueFloat", 0), 1e-6), () -> assertFalse(m_prefs.getBoolean("checkedValueBoolean", true))); } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java index 8b2eeb4459..de5fd1cc0d 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/TimedRobotTest.java @@ -15,7 +15,7 @@ import org.junit.jupiter.api.Test; import org.junit.jupiter.api.parallel.ResourceLock; class TimedRobotTest { - class MockRobot extends TimedRobot { + static class MockRobot extends TimedRobot { public final AtomicInteger m_robotInitCount = new AtomicInteger(0); public final AtomicInteger m_simulationInitCount = new AtomicInteger(0); public final AtomicInteger m_disabledInitCount = new AtomicInteger(0); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/can/CANStatusTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/can/CANStatusTest.java index e83d5fd448..71104fc065 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/can/CANStatusTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/can/CANStatusTest.java @@ -16,6 +16,6 @@ class CANStatusTest { void canStatusGetDoesntThrow() { HAL.initialize(500, 0); CANStatus status = new CANStatus(); - assertDoesNotThrow(() -> CANJNI.GetCANStatus(status)); + assertDoesNotThrow(() -> CANJNI.getCANStatus(status)); } } diff --git a/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.ini b/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.ini index a685de0cad..f271944795 100644 --- a/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.ini +++ b/wpilibj/src/test/resources/edu/wpi/first/wpilibj/PreferencesTestDefault.ini @@ -1,7 +1,8 @@ [NetworkTables Storage 3.0] double "/Preferences/checkedValueInt"=2 +; The omission of a leading zero is intentional for testing purposes double "/Preferences/checkedValueDouble"=.2 -double "/Preferences/checkedValueFloat"=3.14 +double "/Preferences/checkedValueFloat"=3.4 double "/Preferences/checkedValueLong"=172 string "/Preferences/checkedValueString"="Hello. How are you?" boolean "/Preferences/checkedValueBoolean"=false diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Robot.java index 552cff7f69..b8faf6726b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Robot.java @@ -30,11 +30,11 @@ public class Robot extends TimedRobot { public static OI oi; // Initialize the subsystems - public static Drivetrain drivetrain = new Drivetrain(); - public static Collector collector = new Collector(); - public static Shooter shooter = new Shooter(); - public static Pneumatics pneumatics = new Pneumatics(); - public static Pivot pivot = new Pivot(); + public static final Drivetrain drivetrain = new Drivetrain(); + public static final Collector collector = new Collector(); + public static final Shooter shooter = new Shooter(); + public static final Pneumatics pneumatics = new Pneumatics(); + public static final Pivot pivot = new Pivot(); public SendableChooser m_autoChooser; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/oldcommandbased/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/oldcommandbased/Robot.java index d5af6b236f..02b46c53fe 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/oldcommandbased/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/oldcommandbased/Robot.java @@ -19,7 +19,7 @@ import edu.wpi.first.wpilibj.templates.oldcommandbased.subsystems.ExampleSubsyst * project. */ public class Robot extends TimedRobot { - public static ExampleSubsystem m_subsystem = new ExampleSubsystem(); + public static final ExampleSubsystem m_subsystem = new ExampleSubsystem(); public static OI m_oi; Command m_autonomousCommand; diff --git a/wpilibjIntegrationTests/build.gradle b/wpilibjIntegrationTests/build.gradle index 090d30947a..3224345726 100644 --- a/wpilibjIntegrationTests/build.gradle +++ b/wpilibjIntegrationTests/build.gradle @@ -11,7 +11,7 @@ ext { apply from: "${rootDir}/shared/opencv.gradle" -mainClassName = 'edu.wpi.first.wpilibj.test.AntJunitLanucher' +mainClassName = 'edu.wpi.first.wpilibj.test.AntJunitLauncher' apply plugin: 'com.github.johnrengelman.shadow' diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java index fc1b808cf7..c8afb4baa8 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java @@ -183,6 +183,6 @@ public class PIDTest extends AbstractComsSetup { @Test(expected = RuntimeException.class) public void testOnTargetNoToleranceSet() { setupIntegratorRange(); - m_controller.atSetpoint(); + assertFalse(m_controller.atSetpoint()); } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java index 59c943a37e..d5c11e3e53 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java @@ -12,7 +12,7 @@ public class CANStatusTest { @Test public void canStatusGetDoesntThrow() { CANStatus status = new CANStatus(); - CANJNI.GetCANStatus(status); + CANJNI.getCANStatus(status); // Nothing we can assert, so just make sure it didn't throw. } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java index ce46189d47..1dd63daef8 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java @@ -34,10 +34,9 @@ public abstract class AnalogCrossConnectFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup() */ @Override - public boolean setup() { + public void setup() { initialize(); m_output.setVoltage(0); - return true; } /* @@ -46,9 +45,8 @@ public abstract class AnalogCrossConnectFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset() */ @Override - public boolean reset() { + public void reset() { initialize(); - return true; } /* @@ -57,10 +55,9 @@ public abstract class AnalogCrossConnectFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown() */ @Override - public boolean teardown() { + public void teardown() { m_input.close(); m_output.close(); - return true; } /** Analog Output. */ diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java index 7c8b6f07b7..78880d84a7 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java @@ -55,24 +55,20 @@ public class DIOCrossConnectFixture implements ITestFixture { } @Override - public boolean setup() { - return true; - } + public void setup() {} @Override - public boolean reset() { + public void reset() { m_output.set(false); - return true; } @Override - public boolean teardown() { + public void teardown() { logger.log(Level.FINE, "Beginning teardown"); if (m_allocated) { m_input.close(); m_output.close(); m_allocated = false; } - return true; } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java index 2a208a595e..38fbbfc320 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java @@ -67,9 +67,7 @@ public class FakeCounterFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup() */ @Override - public boolean setup() { - return true; - } + public void setup() {} /* * (non-Javadoc) @@ -77,9 +75,8 @@ public class FakeCounterFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset() */ @Override - public boolean reset() { + public void reset() { m_counter.reset(); - return true; } /* @@ -88,7 +85,7 @@ public class FakeCounterFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown() */ @Override - public boolean teardown() { + public void teardown() { logger.log(Level.FINE, "Beginning teardown"); m_counter.close(); m_source.close(); @@ -96,6 +93,5 @@ public class FakeCounterFixture implements ITestFixture { m_dio.teardown(); m_allocated = false; } - return true; } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java index e91602abfd..480185e77f 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java @@ -68,9 +68,7 @@ public class FakeEncoderFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup() */ @Override - public boolean setup() { - return true; - } + public void setup() {} /* * (non-Javadoc) @@ -78,11 +76,10 @@ public class FakeEncoderFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset() */ @Override - public boolean reset() { + public void reset() { m_dio1.reset(); m_dio2.reset(); m_encoder.reset(); - return true; } /* @@ -91,7 +88,7 @@ public class FakeEncoderFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown() */ @Override - public boolean teardown() { + public void teardown() { logger.fine("Beginning teardown"); m_source.close(); logger.finer("Source freed " + m_sourcePort[0] + ", " + m_sourcePort[1]); @@ -101,6 +98,5 @@ public class FakeEncoderFixture implements ITestFixture { m_dio1.teardown(); m_dio2.teardown(); } - return true; } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java index 046e6fe5bb..527606e38c 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java @@ -18,10 +18,8 @@ public interface ITestFixture { /** * Performs any required setup for this fixture, ensuring that all fixture elements are ready for * testing. - * - * @return True if the fixture is ready for testing */ - boolean setup(); + void setup(); /** * Resets the fixture back to test start state. This should be called by the test class in the @@ -29,16 +27,12 @@ public interface ITestFixture { * ITestFixture#setup()} as that is called once, before the class is constructed, so it may need * to start sensors. This method should not have to start anything, just reset sensors and ensure * that motors are stopped. - * - * @return True if the fixture is ready for testing */ - boolean reset(); + void reset(); /** * Performs any required teardown after use of the fixture, ensuring that future tests will not * run into conflicts. - * - * @return True if the teardown succeeded */ - boolean teardown(); + void teardown(); } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java index 492c2d5c3e..220db183e3 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java @@ -82,9 +82,8 @@ public abstract class MotorEncoderFixture implements } @Override - public boolean setup() { + public void setup() { initialize(); - return true; } /** @@ -136,7 +135,7 @@ public abstract class MotorEncoderFixture implements } @Override - public boolean reset() { + public void reset() { initialize(); m_motor.setInverted(false); m_motor.set(0); @@ -145,15 +144,6 @@ public abstract class MotorEncoderFixture implements for (Counter c : m_counters) { c.reset(); } - - boolean wasReset = true; - wasReset = wasReset && m_motor.get() == 0; - wasReset = wasReset && m_encoder.get() == 0; - for (Counter c : m_counters) { - wasReset = wasReset && c.get() == 0; - } - - return wasReset; } /** @@ -163,62 +153,37 @@ public abstract class MotorEncoderFixture implements */ @Override @SuppressWarnings("Regexp") - public boolean teardown() { - String type; - if (m_motor != null) { - type = getType(); - } else { - type = "null"; - } + public void teardown() { if (!m_tornDown) { - boolean wasNull = false; - if (m_motor instanceof PWM && m_motor != null) { - ((PWM) m_motor).close(); + if (m_motor != null) { + if (m_motor instanceof PWM) { + ((PWM) m_motor).close(); + } m_motor = null; - } else if (m_motor == null) { - wasNull = true; } if (m_encoder != null) { m_encoder.close(); m_encoder = null; - } else { - wasNull = true; } if (m_counters[0] != null) { m_counters[0].close(); m_counters[0] = null; - } else { - wasNull = true; } if (m_counters[1] != null) { m_counters[1].close(); m_counters[1] = null; - } else { - wasNull = true; } if (m_alphaSource != null) { m_alphaSource.close(); m_alphaSource = null; - } else { - wasNull = true; } if (m_betaSource != null) { m_betaSource.close(); m_betaSource = null; - } else { - wasNull = true; } m_tornDown = true; - - if (wasNull) { - throw new NullPointerException("MotorEncoderFixture had null params at teardown"); - } - } else { - throw new RuntimeException(type + " Motor Encoder torn down multiple times"); } - - return true; } @Override diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java index a559885db3..3076caf19a 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java @@ -54,9 +54,8 @@ public abstract class RelayCrossConnectFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup() */ @Override - public boolean setup() { + public void setup() { initialize(); - return true; } /* @@ -65,9 +64,8 @@ public abstract class RelayCrossConnectFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset() */ @Override - public boolean reset() { + public void reset() { initialize(); - return true; } /* @@ -76,7 +74,7 @@ public abstract class RelayCrossConnectFixture implements ITestFixture { * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown() */ @Override - public boolean teardown() { + public void teardown() { if (!m_freed) { m_relay.close(); m_inputOne.close(); @@ -88,6 +86,5 @@ public abstract class RelayCrossConnectFixture implements ITestFixture { + RelayCrossConnectFixture.class.getSimpleName() + " multiple times"); } - return true; } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java index 94491d4274..38ea638dd8 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java @@ -10,35 +10,32 @@ package edu.wpi.first.wpilibj.fixtures; */ public class SampleFixture implements ITestFixture { @Override - public boolean setup() { + public void setup() { /* * If this fixture actually accessed the hardware, here is where it would * set up the starting state of the test bench. For example, reseting * encoders, ensuring motors are stopped, reseting any serial communication * if necessary, etc. */ - return true; } @Override - public boolean reset() { + public void reset() { /* * This is where the fixture would reset any sensors or motors used by the * fixture to test default state. This method should not worry about whether * or not the sensors have been allocated correctly, that is the job of the * setup function. */ - return false; } @Override - public boolean teardown() { + public void teardown() { /* * This is where the fixture would deallocate and reset back to normal * conditions any necessary hardware. This includes ensuring motors are * stopped, stoppable sensors are actually stopped, ensuring serial * communications are ready for the next test, etc. */ - return true; } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java index 03c39ab4ec..f41687d805 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java @@ -35,8 +35,7 @@ public abstract class TiltPanCameraFixture implements ITestFixture { public TiltPanCameraFixture() {} @Override - public boolean setup() { - boolean wasSetup = false; + public void setup() { if (!m_initialized) { m_initialized = true; m_tilt = giveTilt(); @@ -48,17 +47,14 @@ public abstract class TiltPanCameraFixture implements ITestFixture { logger.fine("Initializing the gyro"); m_gyro = giveGyro(); m_gyro.reset(); - wasSetup = true; } - return wasSetup; } @Override - public boolean reset() { + public void reset() { if (m_gyro != null) { m_gyro.reset(); } - return true; } public Servo getTilt() { @@ -89,7 +85,7 @@ public abstract class TiltPanCameraFixture implements ITestFixture { } @Override - public boolean teardown() { + public void teardown() { m_tilt.close(); m_tilt = null; m_pan.close(); @@ -102,6 +98,5 @@ public abstract class TiltPanCameraFixture implements ITestFixture { m_gyroParam.close(); m_gyroParam = null; } - return true; } } diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java index 2ce29c9fdd..ac1094ca00 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java @@ -16,7 +16,7 @@ public class FakeCounterSource implements AutoCloseable { private boolean m_allocated; /** Thread object that allows emulation of an encoder. */ - private class EncoderThread extends Thread { + private static class EncoderThread extends Thread { FakeCounterSource m_encoder; EncoderThread(FakeCounterSource encode) { diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java index c305985348..5b91b0cf3e 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java @@ -18,7 +18,7 @@ public class FakeEncoderSource implements AutoCloseable { private final boolean m_allocatedOutputs; /** Thread object that allows emulation of a quadrature encoder. */ - private class QuadEncoderThread extends Thread { + private static class QuadEncoderThread extends Thread { FakeEncoderSource m_encoder; QuadEncoderThread(FakeEncoderSource encode) { diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java index f447dd3193..734115cdc3 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java @@ -201,7 +201,7 @@ public abstract class AbstractComsSetup { * Provided as a replacement to lambda functions to allow for repeatable checks to see if a * correct state is reached. */ - public abstract class BooleanCheck { + public abstract static class BooleanCheck { public BooleanCheck() {} /** diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java index 5871510d6f..ff0542c7b2 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java @@ -59,7 +59,7 @@ public abstract class AbstractTestSuite { * Stores a method name and method class pair. Used when searching for methods matching a given * regex text. */ - protected class ClassMethodPair { + protected static class ClassMethodPair { public final Class m_methodClass; public final String m_methodName; diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java index a1af528e2b..c41ff8a7e9 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java @@ -35,7 +35,7 @@ public class AbstractTestSuiteTest { ExampleSubSuite.class, EmptySuite.class }) - class TestForAbstractTestSuite extends AbstractTestSuite {} + static class TestForAbstractTestSuite extends AbstractTestSuite {} TestForAbstractTestSuite m_testSuite; diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLauncher.java similarity index 98% rename from wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java rename to wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLauncher.java index e860bb0d8d..4dfa6e1d4b 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLauncher.java @@ -16,7 +16,7 @@ import org.apache.tools.ant.taskdefs.optional.junit.JUnitTest; * Provides an entry point for tests to run with ANT. This allows ant to output JUnit XML test * results for Jenkins. */ -public class AntJunitLanucher { +public class AntJunitLauncher { /** * Main entry point for jenkins. * diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java index 0da40ff465..880a97c011 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java @@ -42,6 +42,11 @@ public class TestSuite extends AbstractTestSuite { Logger.getAnonymousLogger().severe("Could not load default logging.properties file"); Logger.getAnonymousLogger().severe(ex.getMessage()); } + try { + inputStream.close(); + } catch (IOException e) { + throw new RuntimeException(e.getMessage()); + } TestBench.out().println("Starting Tests"); } @@ -172,11 +177,11 @@ public class TestSuite extends AbstractTestSuite { for (String s : args) { if (Pattern.matches(METHOD_NAME_FILTER + ".*", s)) { methodFilter = true; - methodRegex = new String(s).replace(METHOD_NAME_FILTER, ""); + methodRegex = s.replace(METHOD_NAME_FILTER, ""); } if (Pattern.matches(METHOD_REPEAT_FILTER + ".*", s)) { try { - repeatCount = Integer.parseInt(new String(s).replace(METHOD_REPEAT_FILTER, "")); + repeatCount = Integer.parseInt(s.replace(METHOD_REPEAT_FILTER, "")); } catch (NumberFormatException ex) { displayInvalidUsage( "The argument passed to the repeat rule was not a valid integer.", args); diff --git a/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java b/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java index fbc9cd3f66..35bac8a0e9 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java +++ b/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java @@ -13,6 +13,8 @@ import org.ejml.simple.SimpleMatrix; @SuppressWarnings("ParameterName") public final class StateSpaceUtil { + private static Random rand = new Random(); + private StateSpaceUtil() { // Utility class } @@ -49,8 +51,6 @@ public final class StateSpaceUtil { * @return White noise vector. */ public static Matrix makeWhiteNoiseVector(Matrix stdDevs) { - var rand = new Random(); - Matrix result = new Matrix<>(new SimpleMatrix(stdDevs.getNumRows(), 1)); for (int i = 0; i < stdDevs.getNumRows(); i++) { result.set(i, 0, rand.nextGaussian() * stdDevs.get(i, 0)); diff --git a/wpimath/src/main/java/edu/wpi/first/math/filter/MedianFilter.java b/wpimath/src/main/java/edu/wpi/first/math/filter/MedianFilter.java index 433a20ca23..c24f6e9139 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/filter/MedianFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/filter/MedianFilter.java @@ -57,13 +57,13 @@ public class MedianFilter { // and remove from ordered list if (curSize > m_size) { m_orderedValues.remove(m_valueBuffer.removeLast()); - curSize = curSize - 1; + --curSize; } // Add next value to circular buffer m_valueBuffer.addFirst(next); - if (curSize % 2 == 1) { + if (curSize % 2 != 0) { // If size is odd, return middle element of sorted list return m_orderedValues.get(curSize / 2); } else { diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java index 7fc6ca4860..6a9c48c132 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java @@ -5,6 +5,7 @@ package edu.wpi.first.math.kinematics; import edu.wpi.first.math.geometry.Rotation2d; +import java.util.Objects; /** Represents the state of one swerve module. */ @SuppressWarnings("MemberName") @@ -29,17 +30,30 @@ public class SwerveModuleState implements Comparable { this.angle = angle; } + @Override + public boolean equals(Object obj) { + if (obj instanceof SwerveModuleState) { + return Double.compare(speedMetersPerSecond, ((SwerveModuleState) obj).speedMetersPerSecond) + == 0; + } + return false; + } + + @Override + public int hashCode() { + return Objects.hash(speedMetersPerSecond); + } + /** * Compares two swerve module states. One swerve module is "greater" than the other if its speed * is higher than the other. * - * @param o The other swerve module. + * @param other The other swerve module. * @return 1 if this is greater, 0 if both are equal, -1 if other is greater. */ @Override - @SuppressWarnings("ParameterName") - public int compareTo(SwerveModuleState o) { - return Double.compare(this.speedMetersPerSecond, o.speedMetersPerSecond); + public int compareTo(SwerveModuleState other) { + return Double.compare(this.speedMetersPerSecond, other.speedMetersPerSecond); } @Override diff --git a/wpimath/src/main/native/include/frc/filter/MedianFilter.h b/wpimath/src/main/native/include/frc/filter/MedianFilter.h index 5a90f4533f..40422a6d24 100644 --- a/wpimath/src/main/native/include/frc/filter/MedianFilter.h +++ b/wpimath/src/main/native/include/frc/filter/MedianFilter.h @@ -45,13 +45,13 @@ class MedianFilter { m_orderedValues.erase(std::find(m_orderedValues.begin(), m_orderedValues.end(), m_valueBuffer.pop_back())); - curSize = curSize - 1; + --curSize; } // Add next value to circular buffer m_valueBuffer.push_front(next); - if (curSize % 2 == 1) { + if (curSize % 2 != 0) { // If size is odd, return middle element of sorted list return m_orderedValues[curSize / 2]; } else { diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java index 350ef18c11..f64608e2b4 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforwardTest.java @@ -38,23 +38,14 @@ class ControlAffinePlantInversionFeedforwardTest { @SuppressWarnings("ParameterName") protected Matrix getDynamics(Matrix x, Matrix u) { - var result = new Matrix<>(Nat.N2(), Nat.N1()); - - result = - Matrix.mat(Nat.N2(), Nat.N2()) - .fill(1.000, 0, 0, 1.000) - .times(x) - .plus(VecBuilder.fill(0, 1).times(u)); - - return result; + return Matrix.mat(Nat.N2(), Nat.N2()) + .fill(1.000, 0, 0, 1.000) + .times(x) + .plus(VecBuilder.fill(0, 1).times(u)); } @SuppressWarnings("ParameterName") protected Matrix getStateDynamics(Matrix x) { - var result = new Matrix<>(Nat.N2(), Nat.N1()); - - result = Matrix.mat(Nat.N2(), Nat.N2()).fill(1.000, 0, 0, 1.000).times(x); - - return result; + return Matrix.mat(Nat.N2(), Nat.N2()).fill(1.000, 0, 0, 1.000).times(x); } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/HolonomicDriveControllerTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/HolonomicDriveControllerTest.java index de5ed9b769..db3f6dcf2a 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/HolonomicDriveControllerTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/HolonomicDriveControllerTest.java @@ -30,7 +30,8 @@ class HolonomicDriveControllerTest { new HolonomicDriveController( new PIDController(1.0, 0.0, 0.0), new PIDController(1.0, 0.0, 0.0), - new ProfiledPIDController(1.0, 0.0, 0.0, new TrapezoidProfile.Constraints(6.28, 3.14))); + new ProfiledPIDController( + 1.0, 0.0, 0.0, new TrapezoidProfile.Constraints(2.0 * Math.PI, Math.PI))); Pose2d robotPose = new Pose2d(2.7, 23.0, Rotation2d.fromDegrees(0.0)); List waypoints = new ArrayList<>(); diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java index ddd834237b..5d9c2b8d31 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/LinearQuadraticRegulatorTest.java @@ -7,52 +7,27 @@ package edu.wpi.first.math.controller; import static org.junit.jupiter.api.Assertions.assertEquals; import edu.wpi.first.math.VecBuilder; -import edu.wpi.first.math.numbers.N1; -import edu.wpi.first.math.numbers.N2; -import edu.wpi.first.math.system.LinearSystem; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import org.junit.jupiter.api.Test; public class LinearQuadraticRegulatorTest { - public static LinearSystem elevatorPlant; - static LinearSystem armPlant; - - static { - createArm(); - createElevator(); - } - + @Test @SuppressWarnings("LocalVariableName") - public static void createArm() { - var motors = DCMotor.getVex775Pro(2); - - var m = 4.0; - var r = 0.4; - var J = 1d / 3d * m * r * r; - var G = 100.0; - - armPlant = LinearSystemId.createSingleJointedArmSystem(motors, J, G); - } - - @SuppressWarnings("LocalVariableName") - public static void createElevator() { + public void testLQROnElevator() { var motors = DCMotor.getVex775Pro(2); var m = 5.0; var r = 0.0181864; var G = 1.0; - elevatorPlant = LinearSystemId.createElevatorSystem(motors, m, r, G); - } - @Test - @SuppressWarnings("LocalVariableName") - public void testLQROnElevator() { + var plant = LinearSystemId.createElevatorSystem(motors, m, r, G); + var qElms = VecBuilder.fill(0.02, 0.4); var rElms = VecBuilder.fill(12.0); var dt = 0.00505; - var controller = new LinearQuadraticRegulator<>(elevatorPlant, qElms, rElms, dt); + var controller = new LinearQuadraticRegulator<>(plant, qElms, rElms, dt); var k = controller.getK(); diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java index 857c47706d..597ae7ffcb 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/LinearSystemLoopTest.java @@ -18,8 +18,6 @@ import edu.wpi.first.math.system.LinearSystemLoop; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.math.trajectory.TrapezoidProfile; -import java.util.ArrayList; -import java.util.List; import java.util.Random; import org.junit.jupiter.api.Test; @@ -103,12 +101,6 @@ public class LinearSystemLoopTest { loop.setNextR(references); - List timeData = new ArrayList<>(); - List xHat = new ArrayList<>(); - List volt = new ArrayList<>(); - List reference = new ArrayList<>(); - List error = new ArrayList<>(); - var time = 0.0; while (time < 10) { if (time > 10) { @@ -128,27 +120,9 @@ public class LinearSystemLoopTest { assertTrue(u >= -12.1 && u <= 12.1, "U out of bounds! Got " + u); - xHat.add(loop.getXHat(0) / 2d / Math.PI * 60); - volt.add(u); - timeData.add(time); - reference.add(references.get(0, 0) / 2d / Math.PI * 60); - error.add(loop.getError(0) / 2d / Math.PI * 60); time += kDt; } - // XYChart bigChart = new XYChartBuilder().build(); - // bigChart.addSeries("Xhat, RPM", timeData, xHat); - // bigChart.addSeries("Reference, RPM", timeData, reference); - // bigChart.addSeries("Error, RPM", timeData, error); - - // XYChart smolChart = new XYChartBuilder().build(); - // smolChart.addSeries("Volts, V", timeData, volt); - - // try { - // new SwingWrapper<>(List.of(bigChart, smolChart)).displayChartMatrix(); - // Thread.sleep(10000000); - // } catch (InterruptedException e) { e.printStackTrace(); } - assertEquals(0.0, loop.getError(0), 0.1); } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java index 3eb2fd7082..18b095b4ef 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/ExtendedKalmanFilterTest.java @@ -22,7 +22,6 @@ import edu.wpi.first.math.system.NumericalJacobian; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.trajectory.TrajectoryConfig; import edu.wpi.first.math.trajectory.TrajectoryGenerator; -import java.util.ArrayList; import java.util.Arrays; import java.util.List; import org.junit.jupiter.api.Test; @@ -127,12 +126,6 @@ public class ExtendedKalmanFilterTest { Matrix nextR = new Matrix<>(Nat.N5(), Nat.N1()); Matrix u = new Matrix<>(Nat.N2(), Nat.N1()); - List trajXs = new ArrayList<>(); - List trajYs = new ArrayList<>(); - - List observerXs = new ArrayList<>(); - List observerYs = new ArrayList<>(); - var B = NumericalJacobian.numericalJacobianU( Nat.N5(), @@ -177,12 +170,6 @@ public class ExtendedKalmanFilterTest { ExtendedKalmanFilterTest::getDynamics, groundTruthX, u, dtSeconds); r = nextR; - - trajXs.add(ref.poseMeters.getTranslation().getX()); - trajYs.add(ref.poseMeters.getTranslation().getY()); - - observerXs.add(observer.getXhat().get(0, 0)); - observerYs.add(observer.getXhat().get(1, 0)); } var localY = getLocalMeasurementModel(observer.getXhat(), u); @@ -192,22 +179,6 @@ public class ExtendedKalmanFilterTest { var R = StateSpaceUtil.makeCostMatrix(VecBuilder.fill(0.01, 0.01, 0.0001, 0.5, 0.5)); observer.correct(Nat.N5(), u, globalY, ExtendedKalmanFilterTest::getGlobalMeasurementModel, R); - // var chartBuilder = new XYChartBuilder(); - // chartBuilder.title = "The Magic of Sensor Fusion, now with a " - // + observer.getClass().getSimpleName(); - // var xyPosChart = chartBuilder.build(); - // - // xyPosChart.setXAxisTitle("X pos, meters"); - // xyPosChart.setYAxisTitle("Y pos, meters"); - // xyPosChart.addSeries("Trajectory", trajXs, trajYs); - // xyPosChart.addSeries("xHat", observerXs, observerYs); - // new SwingWrapper<>(xyPosChart).displayChart(); - // try { - // Thread.sleep(1000000000); - // } catch (InterruptedException ex) { - // ex.printStackTrace(); - // } - var finalPosition = trajectory.sample(trajectory.getTotalTimeSeconds()); assertEquals(finalPosition.poseMeters.getTranslation().getX(), observer.getXhat(0), 1.0); assertEquals(finalPosition.poseMeters.getTranslation().getY(), observer.getXhat(1), 1.0); diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java index 252e6958dc..0a18497a1f 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/KalmanFilterTest.java @@ -21,7 +21,6 @@ import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.math.trajectory.TrajectoryConfig; import edu.wpi.first.math.trajectory.TrajectoryGenerator; -import java.util.ArrayList; import java.util.List; import java.util.Random; import org.junit.jupiter.api.Test; @@ -84,11 +83,6 @@ public class KalmanFilterTest { VecBuilder.fill(2, 2, 2), // measurement weights 0.020); - List xhatsX = new ArrayList<>(); - List measurementsX = new ArrayList<>(); - List xhatsY = new ArrayList<>(); - List measurementsY = new ArrayList<>(); - Matrix measurement; for (int i = 0; i < 100; i++) { // the robot is at [0, 0, 0] so we just park here @@ -98,21 +92,8 @@ public class KalmanFilterTest { // we continue to not accelerate filter.predict(VecBuilder.fill(0.0, 0.0, 0.0), 0.020); - - measurementsX.add(measurement.get(0, 0)); - measurementsY.add(measurement.get(1, 0)); - xhatsX.add(filter.getXhat(0)); - xhatsY.add(filter.getXhat(1)); } - // var chart = new XYChartBuilder().build(); - // chart.addSeries("Xhat, x/y", xhatsX, xhatsY); - // chart.addSeries("Measured position, x/y", measurementsX, measurementsY); - // try { - // new SwingWrapper<>(chart).displayChart(); - // Thread.sleep(10000000); - // } catch (Exception ign) { - // } assertEquals(0.0, filter.getXhat(0), 0.3); assertEquals(0.0, filter.getXhat(0), 0.3); } @@ -131,11 +112,6 @@ public class KalmanFilterTest { VecBuilder.fill(4, 4, 4), // measurement weights 0.020); - List xhatsX = new ArrayList<>(); - List measurementsX = new ArrayList<>(); - List xhatsY = new ArrayList<>(); - List measurementsY = new ArrayList<>(); - // we set the velocity of the robot so that it's moving forward slowly filter.setXhat(0, 0.5); filter.setXhat(1, 0.5); @@ -153,21 +129,8 @@ public class KalmanFilterTest { // we continue to not accelerate filter.predict(VecBuilder.fill(0.0, 0.0, 0.0), 0.020); - - measurementsX.add(measurement.get(0, 0)); - measurementsY.add(measurement.get(1, 0)); - xhatsX.add(filter.getXhat(0)); - xhatsY.add(filter.getXhat(1)); } - // var chart = new XYChartBuilder().build(); - // chart.addSeries("Xhat, x/y", xhatsX, xhatsY); - // chart.addSeries("Measured position, x/y", measurementsX, measurementsY); - // try { - // new SwingWrapper<>(chart).displayChart(); - // Thread.sleep(10000000); - // } catch (Exception ign) {} - assertEquals(0.0, filter.getXhat(0), 0.2); assertEquals(0.0, filter.getXhat(1), 0.2); } @@ -187,11 +150,6 @@ public class KalmanFilterTest { VecBuilder.fill(4, 4, 4), // measurement weights 0.020); - List xhatsX = new ArrayList<>(); - List measurementsX = new ArrayList<>(); - List xhatsY = new ArrayList<>(); - List measurementsY = new ArrayList<>(); - var trajectory = TrajectoryGenerator.generateTrajectory( List.of(new Pose2d(0, 0, new Rotation2d()), new Pose2d(5, 5, new Rotation2d())), @@ -218,23 +176,9 @@ public class KalmanFilterTest { filter.correct(u, measurement); filter.predict(u, 0.020); - measurementsX.add(measurement.get(0, 0)); - measurementsY.add(measurement.get(1, 0)); - xhatsX.add(filter.getXhat(0)); - xhatsY.add(filter.getXhat(1)); - time += 0.020; } - // var chart = new XYChartBuilder().build(); - // chart.addSeries("Xhat, x/y", xhatsX, xhatsY); - // chart.addSeries("Measured position, x/y", measurementsX, measurementsY); - // try { - // new SwingWrapper<>(chart).displayChart(); - // Thread.sleep(10000000); - // } catch (Exception ign) { - // } - assertEquals( trajectory.sample(trajectory.getTotalTimeSeconds()).poseMeters.getTranslation().getX(), filter.getXhat(0), diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java index 586d5c48b1..126459100e 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/UnscentedKalmanFilterTest.java @@ -25,7 +25,6 @@ import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.system.plant.LinearSystemId; import edu.wpi.first.math.trajectory.TrajectoryConfig; import edu.wpi.first.math.trajectory.TrajectoryGenerator; -import java.util.ArrayList; import java.util.Arrays; import java.util.List; import org.junit.jupiter.api.Test; @@ -109,22 +108,6 @@ public class UnscentedKalmanFilterTest { double dtSeconds = 0.00505; double rbMeters = 0.8382 / 2.0; // Robot radius - List trajXs = new ArrayList<>(); - List trajYs = new ArrayList<>(); - - List observerXs = new ArrayList<>(); - List observerYs = new ArrayList<>(); - List observerC = new ArrayList<>(); - List observerS = new ArrayList<>(); - List observervl = new ArrayList<>(); - List observervr = new ArrayList<>(); - - List inputVl = new ArrayList<>(); - List inputVr = new ArrayList<>(); - - List timeData = new ArrayList<>(); - List> rdots = new ArrayList<>(); - UnscentedKalmanFilter observer = new UnscentedKalmanFilter<>( Nat.N6(), @@ -190,25 +173,6 @@ public class UnscentedKalmanFilterTest { var rdot = nextR.minus(r).div(dtSeconds); u = new Matrix<>(B.solve(rdot.minus(getDynamics(r, new Matrix<>(Nat.N2(), Nat.N1()))))); - rdots.add(rdot); - - trajXs.add(ref.poseMeters.getTranslation().getX()); - trajYs.add(ref.poseMeters.getTranslation().getY()); - - observerXs.add(observer.getXhat().get(0, 0)); - observerYs.add(observer.getXhat().get(1, 0)); - - observerC.add(observer.getXhat(2)); - observerS.add(observer.getXhat(3)); - - observervl.add(observer.getXhat(4)); - observervr.add(observer.getXhat(5)); - - inputVl.add(u.get(0, 0)); - inputVr.add(u.get(1, 0)); - - timeData.add(i * dtSeconds); - r = nextR; observer.predict(u, dtSeconds); trueXhat = @@ -233,53 +197,6 @@ public class UnscentedKalmanFilterTest { final var finalPosition = trajectory.sample(trajectory.getTotalTimeSeconds()); - // var chartBuilder = new XYChartBuilder(); - // chartBuilder.title = "The Magic of Sensor Fusion, now with a " - // + observer.getClass().getSimpleName(); - // var xyPosChart = chartBuilder.build(); - - // xyPosChart.setXAxisTitle("X pos, meters"); - // xyPosChart.setYAxisTitle("Y pos, meters"); - // xyPosChart.addSeries("Trajectory", trajXs, trajYs); - // xyPosChart.addSeries("xHat", observerXs, observerYs); - - // var stateChart = new XYChartBuilder() - // .title("States (x-hat)").build(); - // stateChart.addSeries("Cos", timeData, observerC); - // stateChart.addSeries("Sin", timeData, observerS); - // stateChart.addSeries("vl, m/s", timeData, observervl); - // stateChart.addSeries("vr, m/s", timeData, observervr); - - // var inputChart = new XYChartBuilder().title("Inputs").build(); - // inputChart.addSeries("Left voltage", timeData, inputVl); - // inputChart.addSeries("Right voltage", timeData, inputVr); - - // var rdotChart = new XYChartBuilder().title("Rdot").build(); - // rdotChart.addSeries("xdot, or vx", timeData, rdots.stream().map(it -> it.get(0, 0)) - // .collect(Collectors.toList())); - // rdotChart.addSeries("ydot, or vy", timeData, rdots.stream().map(it -> it.get(1, 0)) - // .collect(Collectors.toList())); - // rdotChart.addSeries("cos dot", timeData, rdots.stream().map(it -> it.get(2, 0)) - // .collect(Collectors.toList())); - // rdotChart.addSeries("sin dot", timeData, rdots.stream().map(it -> it.get(3, 0)) - // .collect(Collectors.toList())); - // rdotChart.addSeries("vl dot, or al", timeData, rdots.stream().map(it -> it.get(4, 0)) - // .collect(Collectors.toList())); - // rdotChart.addSeries("vr dot, or ar", timeData, rdots.stream().map(it -> it.get(5, 0)) - // .collect(Collectors.toList())); - - // List charts = new ArrayList<>(); - // charts.add(xyPosChart); - // charts.add(stateChart); - // charts.add(inputChart); - // charts.add(rdotChart); - // new SwingWrapper<>(charts).displayChartMatrix(); - // try { - // Thread.sleep(1000000000); - // } catch (InterruptedException ex) { - // ex.printStackTrace(); - // } - assertEquals(finalPosition.poseMeters.getTranslation().getX(), observer.getXhat(0), 0.25); assertEquals(finalPosition.poseMeters.getTranslation().getY(), observer.getXhat(1), 0.25); assertEquals(finalPosition.poseMeters.getRotation().getRadians(), observer.getXhat(2), 1.0); @@ -302,12 +219,6 @@ public class UnscentedKalmanFilterTest { VecBuilder.fill(1.0), dt); - var time = new ArrayList(); - var refData = new ArrayList(); - var xhat = new ArrayList(); - var udata = new ArrayList(); - var xdotData = new ArrayList(); - var discABPair = Discretization.discretizeAB(plant.getA(), plant.getB(), dt); var discA = discABPair.getFirst(); var discB = discABPair.getSecond(); @@ -315,36 +226,12 @@ public class UnscentedKalmanFilterTest { Matrix ref = VecBuilder.fill(100); Matrix u = VecBuilder.fill(0); - Matrix xdot; for (int i = 0; i < (2.0 / dt); i++) { observer.predict(u, dt); u = discB.solve(ref.minus(discA.times(ref))); - - xdot = plant.getA().times(observer.getXhat()).plus(plant.getB().times(u)); - - time.add(i * dt); - refData.add(ref.get(0, 0)); - xhat.add(observer.getXhat(0)); - udata.add(u.get(0, 0)); - xdotData.add(xdot.get(0, 0)); } - // var chartBuilder = new XYChartBuilder(); - // chartBuilder.title = "The Magic of Sensor Fusion"; - // var chart = chartBuilder.build(); - - // chart.addSeries("Ref", time, refData); - // chart.addSeries("xHat", time, xhat); - // chart.addSeries("input", time, udata); - //// chart.addSeries("xdot", time, xdotData); - - // new SwingWrapper<>(chart).displayChart(); - // try { - // Thread.sleep(1000000000); - // } catch (InterruptedException e) { - // } - assertEquals(ref.get(0, 0), observer.getXhat(0), 5); } diff --git a/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp b/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp index dbec19f169..fb3ad14bce 100644 --- a/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/HolonomicDriveControllerTest.cpp @@ -8,6 +8,7 @@ #include "frc/controller/HolonomicDriveController.h" #include "frc/trajectory/TrajectoryGenerator.h" #include "gtest/gtest.h" +#include "units/angular_acceleration.h" #include "units/math.h" #include "units/time.h" @@ -24,7 +25,8 @@ TEST(HolonomicDriveControllerTest, ReachesReference) { frc::ProfiledPIDController{ 1.0, 0.0, 0.0, frc::TrapezoidProfile::Constraints{ - 6.28_rad_per_s, 3.14_rad_per_s / 1_s}}}; + units::radians_per_second_t{2.0 * wpi::numbers::pi}, + units::radians_per_second_squared_t{wpi::numbers::pi}}}}; frc::Pose2d robotPose{2.7_m, 23_m, frc::Rotation2d{0_deg}}; diff --git a/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java b/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java index 55cf02f1e3..9b23144b45 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/CombinedRuntimeLoader.java @@ -100,7 +100,11 @@ public final class CombinedRuntimeLoader { if (outputFile.toFile().exists()) { continue; } - outputFile.getParent().toFile().mkdirs(); + var parent = outputFile.getParent(); + if (parent == null) { + throw new IOException("Output file has no parent"); + } + parent.toFile().mkdirs(); try (var os = Files.newOutputStream(outputFile)) { int readBytes; diff --git a/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java b/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java index fd22e7ad7f..320bc5bec5 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java @@ -135,6 +135,9 @@ public final class RuntimeDetector { public static boolean isRaspbian() { try (BufferedReader reader = Files.newBufferedReader(Paths.get("/etc/os-release"))) { String value = reader.readLine(); + if (value == null) { + return false; + } return value.contains("Raspbian"); } catch (IOException ex) { return false; diff --git a/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java b/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java index fd9ba37acb..8a2c11af4d 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java @@ -105,7 +105,13 @@ public final class RuntimeLoader { if (resIs == null) { throw new IOException(getLoadErrorMessage(ule)); } - jniLibrary.getParentFile().mkdirs(); + + var parentFile = jniLibrary.getParentFile(); + if (parentFile == null) { + throw new IOException("JNI library has no parent file"); + } + parentFile.mkdirs(); + try (OutputStream os = Files.newOutputStream(jniLibrary.toPath())) { byte[] buffer = new byte[0xFFFF]; // 64K copy buffer int readBytes; @@ -171,7 +177,13 @@ public final class RuntimeLoader { if (resIs == null) { throw new IOException(getLoadErrorMessage(ule)); } - jniLibrary.getParentFile().mkdirs(); + + var parentFile = jniLibrary.getParentFile(); + if (parentFile == null) { + throw new IOException("JNI library has no parent file"); + } + parentFile.mkdirs(); + try (OutputStream os = Files.newOutputStream(jniLibrary.toPath())) { byte[] buffer = new byte[0xFFFF]; // 64K copy buffer int readBytes;