diff --git a/build.gradle b/build.gradle index 51c331e95b..0fcc171685 100644 --- a/build.gradle +++ b/build.gradle @@ -5,7 +5,7 @@ buildscript { mavenCentral() } dependencies { - classpath 'com.hubspot.jinjava:jinjava:2.5.8' + classpath 'com.hubspot.jinjava:jinjava:2.6.0' } } @@ -18,10 +18,10 @@ plugins { id 'edu.wpi.first.GradleVsCode' id 'idea' 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' apply false - id 'com.github.spotbugs' version '5.0.0-beta.1' apply false + id 'net.ltgt.errorprone' version '2.0.2' apply false + id 'com.github.johnrengelman.shadow' version '7.1.0' apply false + id 'com.diffplug.spotless' version '6.0.3' apply false + id 'com.github.spotbugs' version '5.0.0' apply false } wpilibVersioning.buildServerMode = project.hasProperty('buildServer') diff --git a/cameraserver/multiCameraServer/build.gradle b/cameraserver/multiCameraServer/build.gradle index a198cc31dd..f7a78c17d2 100644 --- a/cameraserver/multiCameraServer/build.gradle +++ b/cameraserver/multiCameraServer/build.gradle @@ -27,7 +27,7 @@ repositories { } dependencies { - implementation 'com.google.code.gson:gson:2.8.5' + implementation 'com.google.code.gson:gson:2.8.9' implementation project(':wpiutil') implementation project(':ntcore') diff --git a/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java b/cameraserver/multiCameraServer/src/main/java/edu/wpi/Main.java index f6f91c1baa..622b939129 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; } - static int team; - static boolean server; - static List cameras = new ArrayList<>(); + private static int team; + private static boolean server; + private static List cameras = new ArrayList<>(); private Main() {} diff --git a/gradle.properties b/gradle.properties index fad0c09400..dd4aa687f4 100644 --- a/gradle.properties +++ b/gradle.properties @@ -1 +1,8 @@ -org.gradle.jvmargs=-Xmx1g +# The --add-exports flags work around a bug with spotless and JDK 17 +# https://github.com/diffplug/spotless/issues/834 +org.gradle.jvmargs=-Xmx1g \ + --add-exports jdk.compiler/com.sun.tools.javac.api=ALL-UNNAMED \ + --add-exports jdk.compiler/com.sun.tools.javac.file=ALL-UNNAMED \ + --add-exports jdk.compiler/com.sun.tools.javac.parser=ALL-UNNAMED \ + --add-exports jdk.compiler/com.sun.tools.javac.tree=ALL-UNNAMED \ + --add-exports jdk.compiler/com.sun.tools.javac.util=ALL-UNNAMED diff --git a/hal/src/main/java/edu/wpi/first/hal/HAL.java b/hal/src/main/java/edu/wpi/first/hal/HAL.java index af97450337..53198e0d8d 100644 --- a/hal/src/main/java/edu/wpi/first/hal/HAL.java +++ b/hal/src/main/java/edu/wpi/first/hal/HAL.java @@ -196,8 +196,8 @@ public final class HAL extends JNIWrapper { @SuppressWarnings("MissingJavadocMethod") public static native boolean waitForDSDataTimeout(double timeout); - public static int kMaxJoystickAxes = 12; - public static int kMaxJoystickPOVs = 12; + public static final int kMaxJoystickAxes = 12; + public static final int kMaxJoystickPOVs = 12; public static native short getJoystickAxes(byte joystickNum, float[] axesArray); diff --git a/hal/src/main/java/edu/wpi/first/hal/can/CANExceptionFactory.java b/hal/src/main/java/edu/wpi/first/hal/can/CANExceptionFactory.java index 3c0a4b9f4c..d8fe36e230 100644 --- a/hal/src/main/java/edu/wpi/first/hal/can/CANExceptionFactory.java +++ b/hal/src/main/java/edu/wpi/first/hal/can/CANExceptionFactory.java @@ -14,10 +14,17 @@ public final class CANExceptionFactory { static final int ERR_CANSessionMux_NotAllowed = -44088; static final int ERR_CANSessionMux_NotInitialized = -44089; - @SuppressWarnings("MissingJavadocMethod") - public static void checkStatus(int status, int messageID) - throws CANInvalidBufferException, CANMessageNotAllowedException, CANNotInitializedException, - UncleanStatusException { + /** + * Checks the status of a CAN message with the given message ID. + * + * @param status The CAN status. + * @param messageID The CAN message ID. + * @throws CANInvalidBufferException if the buffer is invalid. + * @throws CANMessageNotAllowedException if the message isn't allowed. + * @throws CANNotInitializedException if the CAN bus isn't initialized. + * @throws UncleanStatusException if the status code passed in reports an error. + */ + public static void checkStatus(int status, int messageID) { switch (status) { case NIRioStatus.kRioStatusSuccess: // Everything is ok... don't throw. diff --git a/shared/java/javacommon.gradle b/shared/java/javacommon.gradle index 2eb14384eb..a40938cad1 100644 --- a/shared/java/javacommon.gradle +++ b/shared/java/javacommon.gradle @@ -104,9 +104,9 @@ tasks.withType(JavaCompile).configureEach { } dependencies { - testImplementation 'org.junit.jupiter:junit-jupiter-api:5.4.2' - testImplementation 'org.junit.jupiter:junit-jupiter-params:5.4.2' - testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.4.2' + testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2' + testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2' + testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2' devImplementation sourceSets.main.output } @@ -120,7 +120,7 @@ task run(type: JavaExec) { build.dependsOn devClasses jacoco { - toolVersion = "0.8.4" + toolVersion = "0.8.7" } jacocoTestReport { diff --git a/shared/java/javastyle.gradle b/shared/java/javastyle.gradle index 281eed3d5f..ffe344c3a6 100644 --- a/shared/java/javastyle.gradle +++ b/shared/java/javastyle.gradle @@ -2,7 +2,7 @@ if (!project.hasProperty('skipJavaFormat')) { apply plugin: 'checkstyle' checkstyle { - toolVersion = "8.38" + toolVersion = "9.2" configDirectory = file("${project.rootDir}/styleguide") config = resources.text.fromFile(new File(configDirectory.get().getAsFile(), "checkstyle.xml")) } @@ -10,7 +10,7 @@ if (!project.hasProperty('skipJavaFormat')) { apply plugin: 'pmd' pmd { - toolVersion = '6.7.0' + toolVersion = '6.41.0' consoleOutput = true reportsDir = file("$project.buildDir/reports/pmd") ruleSetFiles = files(new File(rootDir, "styleguide/pmd-ruleset.xml")) diff --git a/styleguide/checkstyle.xml b/styleguide/checkstyle.xml index 3796fe341f..4b35df8fa5 100644 --- a/styleguide/checkstyle.xml +++ b/styleguide/checkstyle.xml @@ -266,7 +266,7 @@ module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN" value="CLASS_DEF, INTERFACE_DEF, ENUM_DEF, METHOD_DEF, CTOR_DEF, VARIABLE_DEF" /> - + diff --git a/styleguide/pmd-ruleset.xml b/styleguide/pmd-ruleset.xml index bdfb9a785c..0f37af0871 100644 --- a/styleguide/pmd-ruleset.xml +++ b/styleguide/pmd-ruleset.xml @@ -37,6 +37,7 @@ + @@ -60,9 +61,10 @@ + - + @@ -83,8 +85,8 @@ + class="net.sourceforge.pmd.lang.java.rule.codestyle.UnnecessaryCastRule" + externalInfoUrl="https://github.com/pmd/pmd/blob/master/pmd-java/src/main/java/net/sourceforge/pmd/lang/java/rule/codestyle/UnnecessaryCastRule.java" /> + + + + diff --git a/wpilibNewCommands/build.gradle b/wpilibNewCommands/build.gradle index ed81160285..8b4695b9b8 100644 --- a/wpilibNewCommands/build.gradle +++ b/wpilibNewCommands/build.gradle @@ -26,8 +26,7 @@ dependencies { devImplementation project(':hal') devImplementation project(':wpimath') devImplementation project(':wpilibj') - testImplementation 'com.google.guava:guava:19.0' - testImplementation 'org.mockito:mockito-core:2.27.0' + testImplementation 'org.mockito:mockito-core:4.1.0' } nativeUtils.exportsConfigs { diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java index 79be1bf348..0a8284e91b 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java @@ -170,7 +170,7 @@ public final class CommandScheduler implements NTSendable, AutoCloseable { // Do nothing if the scheduler is disabled, the robot is disabled and the command doesn't // run when disabled, or the command is already scheduled. if (m_disabled - || (RobotState.isDisabled() && !command.runsWhenDisabled()) + || RobotState.isDisabled() && !command.runsWhenDisabled() || m_scheduledCommands.containsKey(command)) { return; } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java index d444991742..682fb6bdfb 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java @@ -92,7 +92,7 @@ public class ParallelDeadlineGroup extends CommandGroupBase { if (commandRunning.getKey().isFinished()) { commandRunning.getKey().end(false); commandRunning.setValue(false); - if (commandRunning.getKey() == m_deadline) { + if (commandRunning.getKey().equals(m_deadline)) { m_finished = true; } } 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 88190ed41a..151399df08 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 @@ -13,7 +13,7 @@ import java.util.Set; import org.junit.jupiter.api.BeforeEach; /** Basic setup for all {@link Command tests}." */ -public abstract class CommandTestBase { +public class CommandTestBase { protected CommandTestBase() {} @BeforeEach 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 505801a57f..960c80d894 100644 --- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java +++ b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/PIDBase.java @@ -639,8 +639,8 @@ public class PIDBase implements PIDInterface, PIDOutput, Sendable, AutoCloseable * number of iterations to average with setToleranceBuffer() (defaults to 1). getAvgError() is * used for the onTarget() function. * - * @deprecated Use getError(), which is now already filtered. * @return the current average of the error + * @deprecated Use getError(), which is now already filtered. */ @Deprecated public double getAvgError() { @@ -676,9 +676,9 @@ public class PIDBase implements PIDInterface, PIDOutput, Sendable, AutoCloseable * object. Use it by creating the type of tolerance that you want to use: setTolerance(new * PIDController.AbsoluteTolerance(0.1)) * - * @deprecated Use setPercentTolerance() instead. * @param tolerance A tolerance object of the right type, e.g. PercentTolerance or * AbsoluteTolerance + * @deprecated Use setPercentTolerance() instead. */ @Deprecated public void setTolerance(Tolerance tolerance) { @@ -721,8 +721,8 @@ public class PIDBase implements PIDInterface, PIDOutput, Sendable, AutoCloseable * erroneous measurements when the mechanism is on target. However, the mechanism will not * register as on target for at least the specified bufLength cycles. * - * @deprecated Use a LinearFilter as the input. * @param bufLength Number of previous cycles to average. + * @deprecated Use a LinearFilter as the input. */ @Deprecated public void setToleranceBuffer(int bufLength) { diff --git a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java index 18e0ca6432..367a862861 100644 --- a/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java +++ b/wpilibOldCommands/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java @@ -205,7 +205,7 @@ public class CommandGroup extends Command { } @Override - @SuppressWarnings("MethodName") + @SuppressWarnings({"MethodName", "PMD.AvoidReassigningLoopVariables"}) void _execute() { Entry entry = null; Command cmd = null; @@ -357,6 +357,7 @@ public class CommandGroup extends Command { return true; } + @SuppressWarnings("PMD.AvoidReassigningLoopVariables") private void cancelConflicts(Command command) { for (int i = 0; i < m_children.size(); i++) { Command child = m_children.elementAt(i).m_command; 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 d305595230..55411cc425 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 @@ -11,7 +11,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import org.junit.jupiter.api.BeforeEach; /** The basic test for all {@link Command} tests. */ -public abstract class AbstractCommandTest { +public class AbstractCommandTest { @BeforeEach void commandSetup() { Scheduler.getInstance().removeAll(); diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java index 3a299efae1..d8ef9337db 100644 --- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java +++ b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java @@ -16,7 +16,7 @@ class CommandSequentialGroupTest extends AbstractCommandTest { * timeout. */ @Test - public void testThreeCommandOnSubSystem() { + void testThreeCommandOnSubSystem() { logger.fine("Beginning Test"); final ASubsystem subsystem = new ASubsystem(); diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java index 85f58ea66c..7169c39f45 100644 --- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java +++ b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java @@ -60,12 +60,8 @@ class CommandSupersedeTest extends AbstractCommandTest { void commandFailingSupersedingBecauseFirstCanNotBeInterruptedTest() { final ASubsystem subsystem = new ASubsystem(); - final MockCommand command1 = - new MockCommand(subsystem) { - { - setInterruptible(false); - } - }; + final MockCommand command1 = new MockCommand(subsystem); + command1.setInterruptible(false); final MockCommand command2 = new MockCommand(subsystem); diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java index 698c0e60fc..8539d44755 100644 --- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java +++ b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java @@ -7,7 +7,7 @@ package edu.wpi.first.wpilibj.command; import org.junit.jupiter.api.Test; /** Tests the {@link Command} library. */ -public class DefaultCommandTest extends AbstractCommandTest { +class DefaultCommandTest extends AbstractCommandTest { /** Testing of default commands where the interrupting command ends itself. */ @Test void defaultCommandWhereTheInteruptingCommandEndsItselfTest() { diff --git a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java index 6236e627cc..c7deb235f6 100644 --- a/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java +++ b/wpilibOldCommands/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java @@ -20,7 +20,7 @@ import org.junit.jupiter.api.AfterEach; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -public class ShuffleboardTabTest { +class ShuffleboardTabTest { private NetworkTableInstance m_ntInstance; private ShuffleboardTab m_tab; private ShuffleboardInstance m_instance; diff --git a/wpilibj/build.gradle b/wpilibj/build.gradle index 1004c2030b..665560cbb7 100644 --- a/wpilibj/build.gradle +++ b/wpilibj/build.gradle @@ -66,8 +66,7 @@ dependencies { implementation project(':ntcore') implementation project(':cscore') implementation project(':cameraserver') - testImplementation 'com.google.guava:guava:19.0' - testImplementation 'org.mockito:mockito-core:2.27.0' + testImplementation 'org.mockito:mockito-core:4.1.0' devImplementation project(':hal') devImplementation project(':wpiutil') devImplementation project(':wpimath') diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java index 7090717f88..f5ca67242b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -33,30 +33,16 @@ public class Compressor implements Sendable, AutoCloseable { */ public Compressor(int module, PneumaticsModuleType moduleType) { m_module = PneumaticsBase.getForType(module, moduleType); - boolean allocatedCompressor = false; - boolean successfulCompletion = false; - try { - if (!m_module.reserveCompressor()) { - throw new AllocationException("Compressor already allocated"); - } - - allocatedCompressor = true; - - m_module.enableCompressorDigital(); - - HAL.report(tResourceType.kResourceType_Compressor, module + 1); - SendableRegistry.addLW(this, "Compressor", module); - successfulCompletion = true; - - } finally { - if (!successfulCompletion) { - if (allocatedCompressor) { - m_module.unreserveCompressor(); - } - m_module.close(); - } + if (!m_module.reserveCompressor()) { + m_module.close(); + throw new AllocationException("Compressor already allocated"); } + + m_module.enableCompressorDigital(); + + HAL.report(tResourceType.kResourceType_Compressor, module + 1); + SendableRegistry.addLW(this, "Compressor", module); } /** diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index 68a1bcaa36..d749ccc579 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -53,6 +53,7 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ + @SuppressWarnings("PMD.UseTryWithResources") public DoubleSolenoid( final int module, final PneumaticsModuleType moduleType, diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java index 40384ba80c..9355b4d569 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java @@ -99,7 +99,7 @@ public class Notifier implements AutoCloseable { break; } - Runnable handler = null; + Runnable handler; m_processLock.lock(); try { handler = m_handler; 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 8d1fb07b05..5480f9b11f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -313,7 +313,7 @@ public abstract class RobotBase implements AutoCloseable { private static boolean m_suppressExitWarning; /** Run the robot main loop. */ - @SuppressWarnings("PMD.AvoidCatchingThrowable") + @SuppressWarnings({"PMD.AvoidCatchingThrowable", "PMD.AvoidReassigningCatchVariables"}) private static void runRobot(Supplier robotSupplier) { System.out.println("********** Robot program starting **********"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index e86042b456..bb9be1a0df 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -41,35 +41,22 @@ public class Solenoid implements Sendable, AutoCloseable { */ public Solenoid(final int module, final PneumaticsModuleType moduleType, final int channel) { m_module = PneumaticsBase.getForType(module, moduleType); - boolean allocatedSolenoids = false; - boolean successfulCompletion = false; m_mask = 1 << channel; m_channel = channel; - try { - if (!m_module.checkSolenoidChannel(channel)) { - throw new IllegalArgumentException("Channel " + channel + " out of range"); - } - - if (m_module.checkAndReserveSolenoids(m_mask) != 0) { - throw new AllocationException("Solenoid already allocated"); - } - - allocatedSolenoids = true; - - HAL.report(tResourceType.kResourceType_Solenoid, channel + 1, m_module.getModuleNumber() + 1); - SendableRegistry.addLW(this, "Solenoid", m_module.getModuleNumber(), channel); - successfulCompletion = true; - - } finally { - if (!successfulCompletion) { - if (allocatedSolenoids) { - m_module.unreserveSolenoids(m_mask); - } - m_module.close(); - } + if (!m_module.checkSolenoidChannel(channel)) { + m_module.close(); + throw new IllegalArgumentException("Channel " + channel + " out of range"); } + + if (m_module.checkAndReserveSolenoids(m_mask) != 0) { + m_module.close(); + throw new AllocationException("Solenoid already allocated"); + } + + HAL.report(tResourceType.kResourceType_Solenoid, channel + 1, m_module.getModuleNumber() + 1); + SendableRegistry.addLW(this, "Solenoid", m_module.getModuleNumber(), channel); } @Override diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java index 57fb365789..f9c1c8755c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java @@ -325,8 +325,8 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0); zRotation = MathUtil.clamp(zRotation, -1.0, 1.0); - double leftSpeed = 0.0; - double rightSpeed = 0.0; + double leftSpeed; + double rightSpeed; if (allowTurnInPlace) { leftSpeed = xSpeed + zRotation; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java index 58ac678474..4bfe76c69e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java @@ -59,7 +59,7 @@ final class ContainerHelper { return widget; } - ComplexWidget add(Sendable sendable) throws IllegalArgumentException { + ComplexWidget add(Sendable sendable) { String name = SendableRegistry.getName(sendable); if (name.isEmpty()) { throw new IllegalArgumentException("Sendable must have a name"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java index 8b4e009066..582a7b2763 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java @@ -62,7 +62,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @return the layout with the given title * @throws NoSuchElementException if no layout has yet been defined with the given title */ - ShuffleboardLayout getLayout(String title) throws NoSuchElementException; + ShuffleboardLayout getLayout(String title); /** * Adds a widget to this container to display the given sendable. @@ -73,7 +73,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - ComplexWidget add(String title, Sendable sendable) throws IllegalArgumentException; + ComplexWidget add(String title, Sendable sendable); /** * Adds a widget to this container to display the given video stream. @@ -84,7 +84,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - default ComplexWidget add(String title, VideoSource video) throws IllegalArgumentException { + default ComplexWidget add(String title, VideoSource video) { return add(title, SendableCameraWrapper.wrap(video)); } @@ -120,7 +120,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * title * @see #addPersistent(String, Object) add(String title, Object defaultValue) */ - SimpleWidget add(String title, Object defaultValue) throws IllegalArgumentException; + SimpleWidget add(String title, Object defaultValue); /** * Adds a widget to this container. The widget will display the data provided by the value @@ -133,8 +133,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - SuppliedValueWidget addString(String title, Supplier valueSupplier) - throws IllegalArgumentException; + SuppliedValueWidget addString(String title, Supplier valueSupplier); /** * Adds a widget to this container. The widget will display the data provided by the value @@ -147,8 +146,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - SuppliedValueWidget addNumber(String title, DoubleSupplier valueSupplier) - throws IllegalArgumentException; + SuppliedValueWidget addNumber(String title, DoubleSupplier valueSupplier); /** * Adds a widget to this container. The widget will display the data provided by the value @@ -161,8 +159,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - SuppliedValueWidget addBoolean(String title, BooleanSupplier valueSupplier) - throws IllegalArgumentException; + SuppliedValueWidget addBoolean(String title, BooleanSupplier valueSupplier); /** * Adds a widget to this container. The widget will display the data provided by the value @@ -175,8 +172,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - SuppliedValueWidget addStringArray(String title, Supplier valueSupplier) - throws IllegalArgumentException; + SuppliedValueWidget addStringArray(String title, Supplier valueSupplier); /** * Adds a widget to this container. The widget will display the data provided by the value @@ -189,8 +185,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - SuppliedValueWidget addDoubleArray(String title, Supplier valueSupplier) - throws IllegalArgumentException; + SuppliedValueWidget addDoubleArray(String title, Supplier valueSupplier); /** * Adds a widget to this container. The widget will display the data provided by the value @@ -203,8 +198,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - SuppliedValueWidget addBooleanArray(String title, Supplier valueSupplier) - throws IllegalArgumentException; + SuppliedValueWidget addBooleanArray(String title, Supplier valueSupplier); /** * Adds a widget to this container. The widget will display the data provided by the value @@ -217,8 +211,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * @throws IllegalArgumentException if a widget already exists in this container with the given * title */ - SuppliedValueWidget addRaw(String title, Supplier valueSupplier) - throws IllegalArgumentException; + SuppliedValueWidget addRaw(String title, Supplier valueSupplier); /** * Adds a widget to this container to display a simple piece of data. Unlike {@link #add(String, @@ -232,8 +225,7 @@ public interface ShuffleboardContainer extends ShuffleboardValue { * title * @see #add(String, Object) add(String title, Object defaultValue) */ - default SimpleWidget addPersistent(String title, Object defaultValue) - throws IllegalArgumentException { + default SimpleWidget addPersistent(String title, Object defaultValue) { SimpleWidget widget = add(title, defaultValue); widget.getEntry().setPersistent(); return widget; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java index 726f9cc72a..b48eebbeb5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java @@ -9,7 +9,6 @@ import static edu.wpi.first.wpilibj.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.util.sendable.Sendable; import java.util.List; -import java.util.NoSuchElementException; import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; import java.util.function.Supplier; @@ -34,64 +33,60 @@ public class ShuffleboardLayout extends ShuffleboardComponent addString(String title, Supplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addString(String title, Supplier valueSupplier) { return m_helper.addString(title, valueSupplier); } @Override - public SuppliedValueWidget addNumber(String title, DoubleSupplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addNumber(String title, DoubleSupplier valueSupplier) { return m_helper.addNumber(title, valueSupplier); } @Override - public SuppliedValueWidget addBoolean(String title, BooleanSupplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addBoolean(String title, BooleanSupplier valueSupplier) { return m_helper.addBoolean(title, valueSupplier); } @Override public SuppliedValueWidget addStringArray( - String title, Supplier valueSupplier) throws IllegalArgumentException { + String title, Supplier valueSupplier) { return m_helper.addStringArray(title, valueSupplier); } @Override public SuppliedValueWidget addDoubleArray( - String title, Supplier valueSupplier) throws IllegalArgumentException { + String title, Supplier valueSupplier) { return m_helper.addDoubleArray(title, valueSupplier); } @Override public SuppliedValueWidget addBooleanArray( - String title, Supplier valueSupplier) throws IllegalArgumentException { + String title, Supplier valueSupplier) { return m_helper.addBooleanArray(title, valueSupplier); } @Override - public SuppliedValueWidget addRaw(String title, Supplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addRaw(String title, Supplier valueSupplier) { return m_helper.addRaw(title, valueSupplier); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java index 172d86fe35..597eb80897 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java @@ -7,7 +7,6 @@ package edu.wpi.first.wpilibj.shuffleboard; import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.util.sendable.Sendable; import java.util.List; -import java.util.NoSuchElementException; import java.util.function.BooleanSupplier; import java.util.function.DoubleSupplier; import java.util.function.Supplier; @@ -48,7 +47,7 @@ public final class ShuffleboardTab implements ShuffleboardContainer { } @Override - public ShuffleboardLayout getLayout(String title) throws NoSuchElementException { + public ShuffleboardLayout getLayout(String title) { return m_helper.getLayout(title); } @@ -58,7 +57,7 @@ public final class ShuffleboardTab implements ShuffleboardContainer { } @Override - public ComplexWidget add(Sendable sendable) throws IllegalArgumentException { + public ComplexWidget add(Sendable sendable) { return m_helper.add(sendable); } @@ -68,44 +67,40 @@ public final class ShuffleboardTab implements ShuffleboardContainer { } @Override - public SuppliedValueWidget addString(String title, Supplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addString(String title, Supplier valueSupplier) { return m_helper.addString(title, valueSupplier); } @Override - public SuppliedValueWidget addNumber(String title, DoubleSupplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addNumber(String title, DoubleSupplier valueSupplier) { return m_helper.addNumber(title, valueSupplier); } @Override - public SuppliedValueWidget addBoolean(String title, BooleanSupplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addBoolean(String title, BooleanSupplier valueSupplier) { return m_helper.addBoolean(title, valueSupplier); } @Override public SuppliedValueWidget addStringArray( - String title, Supplier valueSupplier) throws IllegalArgumentException { + String title, Supplier valueSupplier) { return m_helper.addStringArray(title, valueSupplier); } @Override public SuppliedValueWidget addDoubleArray( - String title, Supplier valueSupplier) throws IllegalArgumentException { + String title, Supplier valueSupplier) { return m_helper.addDoubleArray(title, valueSupplier); } @Override public SuppliedValueWidget addBooleanArray( - String title, Supplier valueSupplier) throws IllegalArgumentException { + String title, Supplier valueSupplier) { return m_helper.addBooleanArray(title, valueSupplier); } @Override - public SuppliedValueWidget addRaw(String title, Supplier valueSupplier) - throws IllegalArgumentException { + public SuppliedValueWidget addRaw(String title, Supplier valueSupplier) { return m_helper.addRaw(title, valueSupplier); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java index 2614edfa32..cece5a9e44 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java @@ -72,9 +72,9 @@ public class SendableChooser implements NTSendable, AutoCloseable { /** * Adds the given object to the list of options. * - * @deprecated Use {@link #addOption(String, Object)} instead. * @param name the name of the option * @param object the option + * @deprecated Use {@link #addOption(String, Object)} instead. */ @Deprecated public void addObject(String name, V object) { @@ -99,9 +99,9 @@ public class SendableChooser implements NTSendable, AutoCloseable { /** * Adds the given object to the list of options and marks it as the default. * - * @deprecated Use {@link #setDefaultOption(String, Object)} instead. * @param name the name of the option * @param object the option + * @deprecated Use {@link #setDefaultOption(String, Object)} instead. */ @Deprecated public void addDefault(String name, V object) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java index 2a24dbe6cd..031d411bdb 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java @@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj; import static org.junit.jupiter.api.Assertions.assertAll; import static org.junit.jupiter.api.Assertions.assertEquals; -import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.params.provider.Arguments.arguments; import edu.wpi.first.wpilibj.util.Color; @@ -63,13 +62,13 @@ class AddressableLEDBufferTest { buffer.setLED(2, Color.kFirstRed); buffer.setLED(3, Color.kFirstBlue); - assertTrue(buffer.getLED(0).equals(Color.kFirstBlue)); - assertTrue(buffer.getLED(1).equals(Color.kDenim)); - assertTrue(buffer.getLED(2).equals(Color.kFirstRed)); - assertTrue(buffer.getLED(3).equals(Color.kFirstBlue)); - assertTrue(buffer.getLED8Bit(0).equals(firstBlueColor8Bit)); - assertTrue(buffer.getLED8Bit(1).equals(denimColor8Bit)); - assertTrue(buffer.getLED8Bit(2).equals(firstRedColor8Bit)); - assertTrue(buffer.getLED8Bit(3).equals(firstBlueColor8Bit)); + assertEquals(Color.kFirstBlue, buffer.getLED(0)); + assertEquals(Color.kDenim, buffer.getLED(1)); + assertEquals(Color.kFirstRed, buffer.getLED(2)); + assertEquals(Color.kFirstBlue, buffer.getLED(3)); + assertEquals(firstBlueColor8Bit, buffer.getLED8Bit(0)); + assertEquals(denimColor8Bit, buffer.getLED8Bit(1)); + assertEquals(firstRedColor8Bit, buffer.getLED8Bit(2)); + assertEquals(firstBlueColor8Bit, buffer.getLED8Bit(3)); } } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogGyroTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogGyroTest.java index c8eaad9b95..daae493e53 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogGyroTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogGyroTest.java @@ -12,7 +12,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.simulation.AnalogGyroSim; import org.junit.jupiter.api.Test; -public class AnalogGyroTest { +class AnalogGyroTest { @Test void testInitializeWithAnalogInput() { HAL.initialize(500, 0); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java index fa299a5305..7c6536e123 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java @@ -11,7 +11,7 @@ import edu.wpi.first.wpilibj.simulation.AnalogInputSim; import edu.wpi.first.wpilibj.simulation.RoboRioSim; import org.junit.jupiter.api.Test; -public class AnalogPotentiometerTest { +class AnalogPotentiometerTest { @Test void testInitializeWithAnalogInput() { HAL.initialize(500, 0); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DebouncerTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DebouncerTest.java index 5a51f6c0fb..05d91aaadf 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DebouncerTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DebouncerTest.java @@ -10,7 +10,7 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.wpilibj.simulation.SimHooks; import org.junit.jupiter.api.Test; -public class DebouncerTest { +class DebouncerTest { @Test void debounceRisingTest() { var debouncer = new Debouncer(0.02, Debouncer.DebounceType.kRising); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DigitalOutputTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DigitalOutputTest.java index 47b7eda5f6..e83b59c907 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DigitalOutputTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DigitalOutputTest.java @@ -12,7 +12,7 @@ import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.simulation.DIOSim; import org.junit.jupiter.api.Test; -public class DigitalOutputTest { +class DigitalOutputTest { @Test void testDefaultFunctions() { try (DigitalOutput output = new DigitalOutput(0)) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestCTRE.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestCTRE.java index 72a3e896fe..9e2971eebb 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestCTRE.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestCTRE.java @@ -10,7 +10,7 @@ import static org.junit.jupiter.api.Assertions.assertThrows; import edu.wpi.first.hal.util.AllocationException; import org.junit.jupiter.api.Test; -public class DoubleSolenoidTestCTRE { +class DoubleSolenoidTestCTRE { @Test void testValidInitialization() { try (DoubleSolenoid solenoid = new DoubleSolenoid(3, PneumaticsModuleType.CTREPCM, 2, 3)) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestREV.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestREV.java index 888b67749a..15e88c5449 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestREV.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/DoubleSolenoidTestREV.java @@ -10,7 +10,7 @@ import static org.junit.jupiter.api.Assertions.assertThrows; import edu.wpi.first.hal.util.AllocationException; import org.junit.jupiter.api.Test; -public class DoubleSolenoidTestREV { +class DoubleSolenoidTestREV { @Test void testValidInitialization() { try (DoubleSolenoid solenoid = new DoubleSolenoid(3, PneumaticsModuleType.REVPH, 2, 3)) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java index 2eecd66f04..bc32b8e346 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java @@ -12,7 +12,7 @@ import java.util.concurrent.atomic.AtomicBoolean; import java.util.concurrent.atomic.AtomicInteger; import org.junit.jupiter.api.Test; -public class InterruptTest { +class InterruptTest { @Test void testAsynchronousInterrupt() { AtomicBoolean hasFired = new AtomicBoolean(false); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java index e969cb3eb6..c1ebd51f21 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java @@ -19,7 +19,7 @@ class PS4ControllerTest { @ParameterizedTest @EnumSource(value = PS4Controller.Button.class) @SuppressWarnings({"VariableDeclarationUsageDistance"}) - public void testButtons(PS4Controller.Button button) + void testButtons(PS4Controller.Button button) throws NoSuchMethodException, InvocationTargetException, IllegalAccessException { HAL.initialize(500, 0); PS4Controller joy = new PS4Controller(2); @@ -60,7 +60,7 @@ class PS4ControllerTest { @ParameterizedTest @EnumSource(value = PS4Controller.Axis.class) @SuppressWarnings({"VariableDeclarationUsageDistance"}) - public void testAxes(PS4Controller.Axis axis) + void testAxes(PS4Controller.Axis axis) throws NoSuchMethodException, InvocationTargetException, IllegalAccessException { HAL.initialize(500, 0); PS4Controller joy = new PS4Controller(2); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java index a33716cdfd..bf6876e5a2 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SensorUtilTest.java @@ -9,7 +9,7 @@ import static org.junit.jupiter.api.Assertions.assertThrows; import org.junit.jupiter.api.Test; -public class SensorUtilTest { +class SensorUtilTest { @Test void checkAnalogInputChannel() { assertThrows(IllegalArgumentException.class, () -> SensorUtil.checkAnalogInputChannel(100)); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestCTRE.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestCTRE.java index 0077650444..1712046786 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestCTRE.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestCTRE.java @@ -12,7 +12,7 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.hal.util.AllocationException; import org.junit.jupiter.api.Test; -public class SolenoidTestCTRE { +class SolenoidTestCTRE { @Test void testValidInitialization() { try (Solenoid solenoid = new Solenoid(3, PneumaticsModuleType.CTREPCM, 2)) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestREV.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestREV.java index 3f07406bda..eb327d4dc7 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestREV.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/SolenoidTestREV.java @@ -12,7 +12,7 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.hal.util.AllocationException; import org.junit.jupiter.api.Test; -public class SolenoidTestREV { +class SolenoidTestREV { @Test void testValidInitialization() { try (Solenoid solenoid = new Solenoid(3, PneumaticsModuleType.REVPH, 2)) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java index 1b505723db..a7ab0ca2fe 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/UltrasonicTest.java @@ -11,9 +11,9 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.wpilibj.simulation.UltrasonicSim; import org.junit.jupiter.api.Test; -public class UltrasonicTest { +class UltrasonicTest { @Test - public void testUltrasonic() { + void testUltrasonic() { try (Ultrasonic ultrasonic = new Ultrasonic(0, 1)) { UltrasonicSim sim = new UltrasonicSim(ultrasonic); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java index 8eed93f9ba..0501f6d8b0 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java @@ -34,19 +34,20 @@ public abstract class UtilityClassTest { } @Test - public void singleConstructorTest() { + void singleConstructorTest() { assertEquals(1, m_clazz.getDeclaredConstructors().length, "More than one constructor defined"); } @Test - public void constructorPrivateTest() { + void constructorPrivateTest() { Constructor constructor = m_clazz.getDeclaredConstructors()[0]; assertFalse(constructor.canAccess(null), "Constructor is not private"); } @Test - public void constructorReflectionTest() { + @SuppressWarnings("PMD.AvoidAccessibilityAlteration") + void constructorReflectionTest() { Constructor constructor = m_clazz.getDeclaredConstructors()[0]; constructor.setAccessible(true); assertThrows(InvocationTargetException.class, constructor::newInstance); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java index d472377eba..af9c902fe2 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java @@ -19,7 +19,7 @@ class XboxControllerTest { @ParameterizedTest @EnumSource(value = XboxController.Button.class) @SuppressWarnings({"VariableDeclarationUsageDistance"}) - public void testButtons(XboxController.Button button) + void testButtons(XboxController.Button button) throws NoSuchMethodException, InvocationTargetException, IllegalAccessException { HAL.initialize(500, 0); XboxController joy = new XboxController(2); @@ -60,7 +60,7 @@ class XboxControllerTest { @ParameterizedTest @EnumSource(value = XboxController.Axis.class) @SuppressWarnings({"VariableDeclarationUsageDistance"}) - public void testAxes(XboxController.Axis axis) + void testAxes(XboxController.Axis axis) throws NoSuchMethodException, InvocationTargetException, IllegalAccessException { HAL.initialize(500, 0); XboxController joy = new XboxController(2); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java index 61db14a799..5dfad6796d 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java @@ -15,7 +15,7 @@ import org.junit.jupiter.api.AfterEach; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -public class ShuffleboardInstanceTest { +class ShuffleboardInstanceTest { private NetworkTableInstance m_ntInstance; private ShuffleboardInstance m_shuffleboardInstance; diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTest.java index 963d26296b..f4c8a8fbfd 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTest.java @@ -9,8 +9,8 @@ import static org.junit.jupiter.api.Assertions.assertSame; import edu.wpi.first.wpilibj.UtilityClassTest; import org.junit.jupiter.api.Test; -public class ShuffleboardTest extends UtilityClassTest { - public ShuffleboardTest() { +class ShuffleboardTest extends UtilityClassTest { + ShuffleboardTest() { super(Shuffleboard.class); } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java index 7f4103825d..559526132e 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL345SimTest.java @@ -15,7 +15,7 @@ import edu.wpi.first.wpilibj.interfaces.Accelerometer; import org.junit.jupiter.params.ParameterizedTest; import org.junit.jupiter.params.provider.EnumSource; -public class ADXL345SimTest { +class ADXL345SimTest { @ParameterizedTest @EnumSource(Accelerometer.Range.class) void testInitI2C(Accelerometer.Range range) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java index f361381555..7ab6b6be17 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ADXL362SimTest.java @@ -13,7 +13,7 @@ import edu.wpi.first.wpilibj.interfaces.Accelerometer; import org.junit.jupiter.params.ParameterizedTest; import org.junit.jupiter.params.provider.EnumSource; -public class ADXL362SimTest { +class ADXL362SimTest { @ParameterizedTest @EnumSource(Accelerometer.Range.class) void testAccel(Accelerometer.Range range) { diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogEncoderSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogEncoderSimTest.java index 5a04441ad5..a04ce10bb0 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogEncoderSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/AnalogEncoderSimTest.java @@ -11,9 +11,9 @@ import edu.wpi.first.wpilibj.AnalogEncoder; import edu.wpi.first.wpilibj.AnalogInput; import org.junit.jupiter.api.Test; -public class AnalogEncoderSimTest { +class AnalogEncoderSimTest { @Test - public void testBasic() { + void testBasic() { try (var analogInput = new AnalogInput(0); var analogEncoder = new AnalogEncoder(analogInput)) { var encoderSim = new AnalogEncoderSim(analogEncoder); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java index 62fdcc965b..52c446c404 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSimTest.java @@ -30,7 +30,7 @@ import org.junit.jupiter.api.Test; class DifferentialDrivetrainSimTest { @Test - public void testConvergence() { + void testConvergence() { var motor = DCMotor.getNEO(2); var plant = LinearSystemId.createDrivetrainVelocitySystem( @@ -96,7 +96,7 @@ class DifferentialDrivetrainSimTest { } @Test - public void testCurrent() { + void testCurrent() { var motor = DCMotor.getNEO(2); var plant = LinearSystemId.createDrivetrainVelocitySystem( @@ -126,7 +126,7 @@ class DifferentialDrivetrainSimTest { } @Test - public void testModelStability() { + void testModelStability() { var motor = DCMotor.getNEO(2); var plant = LinearSystemId.createDrivetrainVelocitySystem( diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java index ce50afc3b5..fb0a058f37 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/DriverStationSimTest.java @@ -18,7 +18,7 @@ import org.junit.jupiter.api.Test; import org.junit.jupiter.params.ParameterizedTest; import org.junit.jupiter.params.provider.EnumSource; -public class DriverStationSimTest { +class DriverStationSimTest { @Test void testEnabled() { HAL.initialize(500, 0); @@ -192,7 +192,7 @@ public class DriverStationSimTest { @ParameterizedTest @EnumSource(DriverStation.MatchType.class) - public void testMatchType(DriverStation.MatchType matchType) { + void testMatchType(DriverStation.MatchType matchType) { HAL.initialize(500, 0); DriverStationSim.resetData(); @@ -202,7 +202,7 @@ public class DriverStationSimTest { } @Test - public void testReplayNumber() { + void testReplayNumber() { HAL.initialize(500, 0); DriverStationSim.resetData(); @@ -212,7 +212,7 @@ public class DriverStationSimTest { } @Test - public void testMatchNumber() { + void testMatchNumber() { HAL.initialize(500, 0); DriverStationSim.resetData(); @@ -222,7 +222,7 @@ public class DriverStationSimTest { } @Test - public void testMatchTime() { + void testMatchTime() { HAL.initialize(500, 0); DriverStationSim.resetData(); @@ -238,7 +238,7 @@ public class DriverStationSimTest { } @Test - public void testSetGameSpecificMessage() { + void testSetGameSpecificMessage() { HAL.initialize(500, 0); DriverStationSim.resetData(); @@ -249,7 +249,7 @@ public class DriverStationSimTest { } @Test - public void testSetEventName() { + void testSetEventName() { HAL.initialize(500, 0); DriverStationSim.resetData(); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java index d655a90f8a..a2e0ef4657 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/ElevatorSimTest.java @@ -17,10 +17,10 @@ import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX; import org.junit.jupiter.api.Test; -public class ElevatorSimTest { +class ElevatorSimTest { @Test @SuppressWarnings({"LocalVariableName", "resource"}) - public void testStateSpaceSimWithElevator() { + void testStateSpaceSimWithElevator() { RoboRioSim.resetData(); var controller = new PIDController(10, 0, 0); @@ -61,7 +61,7 @@ public class ElevatorSimTest { } @Test - public void testMinMax() { + void testMinMax() { var plant = LinearSystemId.createElevatorSystem( DCMotor.getVex775Pro(4), 8.0, 0.75 * 25.4 / 1000.0, 14.67); @@ -92,7 +92,7 @@ public class ElevatorSimTest { } @Test - public void testStability() { + void testStability() { var sim = new ElevatorSim(DCMotor.getVex775Pro(4), 100, 4, Units.inchesToMeters(0.5), 0, 10); sim.setState(VecBuilder.fill(0, 0)); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java index e9ea9f1145..c1988b3e37 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/RoboRioSimTest.java @@ -15,7 +15,7 @@ import edu.wpi.first.wpilibj.simulation.testutils.DoubleCallback; import edu.wpi.first.wpilibj.simulation.testutils.IntCallback; import org.junit.jupiter.api.Test; -public class RoboRioSimTest { +class RoboRioSimTest { @Test void testFPGAButton() { RoboRioSim.resetData(); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java index 26aa6b9730..1be29a9da4 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSimTest.java @@ -11,7 +11,7 @@ import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.math.util.Units; import org.junit.jupiter.api.Test; -public class SingleJointedArmSimTest { +class SingleJointedArmSimTest { SingleJointedArmSim m_sim = new SingleJointedArmSim( DCMotor.getVex775Pro(2), @@ -24,7 +24,7 @@ public class SingleJointedArmSimTest { true); @Test - public void testArmDisabled() { + void testArmDisabled() { m_sim.setState(VecBuilder.fill(0.0, 0.0)); for (int i = 0; i < 12 / 0.02; i++) { diff --git a/wpilibjExamples/build.gradle b/wpilibjExamples/build.gradle index 518b1e86e9..7d74e80ab0 100644 --- a/wpilibjExamples/build.gradle +++ b/wpilibjExamples/build.gradle @@ -37,13 +37,13 @@ dependencies { implementation project(':wpilibOldCommands') implementation project(':wpilibNewCommands') - testImplementation 'org.junit.jupiter:junit-jupiter-api:5.4.2' - testImplementation 'org.junit.jupiter:junit-jupiter-params:5.4.2' - testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.4.2' + testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2' + testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2' + testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2' } jacoco { - toolVersion = "0.8.4" + toolVersion = "0.8.7" } jacocoTestReport { diff --git a/wpilibjIntegrationTests/build.gradle b/wpilibjIntegrationTests/build.gradle index 3224345726..d2daedaec1 100644 --- a/wpilibjIntegrationTests/build.gradle +++ b/wpilibjIntegrationTests/build.gradle @@ -27,11 +27,11 @@ dependencies { implementation project(':ntcore') implementation project(':cscore') implementation project(':cameraserver') - implementation 'junit:junit:4.11' + implementation 'junit:junit:4.13.2' testImplementation 'org.hamcrest:hamcrest-all:1.3' - implementation 'com.googlecode.junit-toolbox:junit-toolbox:2.0' - implementation 'org.apache.ant:ant:1.9.4' - implementation 'org.apache.ant:ant-junit:1.9.4' + implementation 'com.googlecode.junit-toolbox:junit-toolbox:2.4' + implementation 'org.apache.ant:ant:1.10.12' + implementation 'org.apache.ant:ant-junit:1.10.12' } build.dependsOn shadowJar diff --git a/wpimath/build.gradle b/wpimath/build.gradle index 110eb91acc..c31f04c764 100644 --- a/wpimath/build.gradle +++ b/wpimath/build.gradle @@ -33,9 +33,9 @@ model { dependencies { api "org.ejml:ejml-simple:0.41" - api "com.fasterxml.jackson.core:jackson-annotations:2.10.0" - api "com.fasterxml.jackson.core:jackson-core:2.10.0" - api "com.fasterxml.jackson.core:jackson-databind:2.10.0" + api "com.fasterxml.jackson.core:jackson-annotations:2.12.4" + api "com.fasterxml.jackson.core:jackson-core:2.12.4" + api "com.fasterxml.jackson.core:jackson-databind:2.12.4" } def wpilibNumberFileInput = file("src/generate/GenericNumber.java.jinja") diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java index cf4b26dea8..bcd6f731c9 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java @@ -104,10 +104,11 @@ public class LinearQuadraticRegulator distToTarget) { accelDist = distToTarget; diff --git a/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc b/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc index 47a598ee47..4ec0f42c71 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc +++ b/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.inc @@ -104,8 +104,6 @@ units::second_t TrapezoidProfile::TimeLeftUntil( endAccel = units::math::max(endAccel, 0_s); endFullSpeed = units::math::max(endFullSpeed, 0_s); - units::second_t endDeccel = m_endDeccel - endAccel - endFullSpeed; - endDeccel = units::math::max(endDeccel, 0_s); const Acceleration_t acceleration = m_constraints.maxAcceleration; const Acceleration_t decceleration = -m_constraints.maxAcceleration; @@ -127,20 +125,16 @@ units::second_t TrapezoidProfile::TimeLeftUntil( deccelVelocity = velocity; } - Distance_t deccelDist = - deccelVelocity * endDeccel + 0.5 * decceleration * endDeccel * endDeccel; - - deccelDist = units::math::max(deccelDist, Distance_t(0)); - Distance_t fullSpeedDist = m_constraints.maxVelocity * endFullSpeed; + Distance_t deccelDist; if (accelDist > distToTarget) { accelDist = distToTarget; - fullSpeedDist = Distance_t(0); - deccelDist = Distance_t(0); + fullSpeedDist = Distance_t{0}; + deccelDist = Distance_t{0}; } else if (accelDist + fullSpeedDist > distToTarget) { fullSpeedDist = distToTarget - accelDist; - deccelDist = Distance_t(0); + deccelDist = Distance_t{0}; } else { deccelDist = distToTarget - fullSpeedDist - accelDist; } diff --git a/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java b/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java index 4140faebeb..66daf3d4ce 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/DrakeTest.java @@ -11,7 +11,7 @@ import org.ejml.simple.SimpleMatrix; import org.junit.jupiter.api.Test; @SuppressWarnings({"ParameterName", "LocalVariableName"}) -public class DrakeTest { +class DrakeTest { public static void assertMatrixEqual(SimpleMatrix A, SimpleMatrix B) { for (int i = 0; i < A.numRows(); i++) { for (int j = 0; j < A.numCols(); j++) { @@ -49,7 +49,7 @@ public class DrakeTest { } @Test - public void testDiscreteAlgebraicRicattiEquation() { + void testDiscreteAlgebraicRicattiEquation() { int n1 = 4; int m1 = 1; diff --git a/wpimath/src/test/java/edu/wpi/first/math/MatrixTest.java b/wpimath/src/test/java/edu/wpi/first/math/MatrixTest.java index 45df8fe929..8ee11e5e22 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/MatrixTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/MatrixTest.java @@ -15,7 +15,7 @@ import edu.wpi.first.math.numbers.N4; import org.ejml.data.SingularMatrixException; import org.junit.jupiter.api.Test; -public class MatrixTest { +class MatrixTest { @Test void testMatrixMultiplication() { var mat1 = Matrix.mat(Nat.N2(), Nat.N2()).fill(2.0, 1.0, 0.0, 1.0); diff --git a/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java b/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java index 456506c70c..8cd1e5a47d 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/StateSpaceUtilTest.java @@ -18,9 +18,9 @@ import org.ejml.dense.row.MatrixFeatures_DDRM; import org.ejml.simple.SimpleMatrix; import org.junit.jupiter.api.Test; -public class StateSpaceUtilTest { +class StateSpaceUtilTest { @Test - public void testCostArray() { + void testCostArray() { var mat = StateSpaceUtil.makeCostMatrix(VecBuilder.fill(1.0, 2.0, 3.0)); assertEquals(1.0, mat.get(0, 0), 1e-3); @@ -35,7 +35,7 @@ public class StateSpaceUtilTest { } @Test - public void testCovArray() { + void testCovArray() { var mat = StateSpaceUtil.makeCovarianceMatrix(Nat.N3(), VecBuilder.fill(1.0, 2.0, 3.0)); assertEquals(1.0, mat.get(0, 0), 1e-3); @@ -51,7 +51,7 @@ public class StateSpaceUtilTest { @Test @SuppressWarnings("LocalVariableName") - public void testIsStabilizable() { + void testIsStabilizable() { Matrix A; Matrix B = VecBuilder.fill(0, 1); @@ -78,7 +78,7 @@ public class StateSpaceUtilTest { @Test @SuppressWarnings("LocalVariableName") - public void testIsDetectable() { + void testIsDetectable() { Matrix A; Matrix C = Matrix.mat(Nat.N1(), Nat.N2()).fill(0, 1); @@ -104,7 +104,7 @@ public class StateSpaceUtilTest { } @Test - public void testMakeWhiteNoiseVector() { + void testMakeWhiteNoiseVector() { var firstData = new ArrayList(); var secondData = new ArrayList(); for (int i = 0; i < 1000; i++) { @@ -135,7 +135,7 @@ public class StateSpaceUtilTest { } @Test - public void testMatrixExp() { + void testMatrixExp() { Matrix wrappedMatrix = Matrix.eye(Nat.N2()); var wrappedResult = wrappedMatrix.exp(); @@ -152,7 +152,7 @@ public class StateSpaceUtilTest { } @Test - public void testSimpleMatrixExp() { + void testSimpleMatrixExp() { SimpleMatrix matrix = SimpleMatrixUtils.eye(2); var result = SimpleMatrixUtils.exp(matrix); @@ -175,7 +175,7 @@ public class StateSpaceUtilTest { } @Test - public void testPoseToVector() { + void testPoseToVector() { Pose2d pose = new Pose2d(1, 2, new Rotation2d(3)); var vector = StateSpaceUtil.poseToVector(pose); assertEquals(pose.getTranslation().getX(), vector.get(0, 0), 1e-6); diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangInputOutputTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangInputOutputTest.java index 3621ea3e0d..9e1f6f2a72 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangInputOutputTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangInputOutputTest.java @@ -9,7 +9,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -public class BangBangInputOutputTest { +class BangBangInputOutputTest { private BangBangController m_controller; @BeforeEach diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangToleranceTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangToleranceTest.java index 8af90542da..bcf688b98d 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangToleranceTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/BangBangToleranceTest.java @@ -10,7 +10,7 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -public class BangBangToleranceTest { +class BangBangToleranceTest { private BangBangController m_controller; @BeforeEach 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 5d9c2b8d31..7659f2bd12 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 @@ -11,10 +11,10 @@ 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 { +class LinearQuadraticRegulatorTest { @Test @SuppressWarnings("LocalVariableName") - public void testLQROnElevator() { + void testLQROnElevator() { var motors = DCMotor.getVex775Pro(2); var m = 5.0; @@ -36,7 +36,7 @@ public class LinearQuadraticRegulatorTest { } @Test - public void testFourMotorElevator() { + void testFourMotorElevator() { var dt = 0.020; var plant = @@ -52,7 +52,7 @@ public class LinearQuadraticRegulatorTest { @Test @SuppressWarnings("LocalVariableName") - public void testLQROnArm() { + void testLQROnArm() { var motors = DCMotor.getVex775Pro(2); var m = 4.0; @@ -74,7 +74,7 @@ public class LinearQuadraticRegulatorTest { } @Test - public void testLatencyCompensate() { + void testLatencyCompensate() { var dt = 0.02; var plant = 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 597ae7ffcb..5fa4939f7e 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 @@ -21,8 +21,8 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile; import java.util.Random; import org.junit.jupiter.api.Test; -public class LinearSystemLoopTest { - public static final double kDt = 0.00505; +class LinearSystemLoopTest { + private static final double kDt = 0.00505; private static final double kPositionStddev = 0.0001; private static final Random random = new Random(); @@ -51,7 +51,7 @@ public class LinearSystemLoopTest { @Test @SuppressWarnings("LocalVariableName") - public void testStateSpaceEnabled() { + void testStateSpaceEnabled() { m_loop.reset(VecBuilder.fill(0, 0)); Matrix references = VecBuilder.fill(2.0, 0.0); var constraints = new TrapezoidProfile.Constraints(4, 3); @@ -80,7 +80,7 @@ public class LinearSystemLoopTest { @Test @SuppressWarnings("LocalVariableName") - public void testFlywheelEnabled() { + void testFlywheelEnabled() { LinearSystem plant = LinearSystemId.createFlywheelSystem(DCMotor.getNEO(2), 0.00289, 1.0); KalmanFilter observer = diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/AngleStatisticsTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/AngleStatisticsTest.java index 9fcf5e31c4..c36e72f663 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/AngleStatisticsTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/AngleStatisticsTest.java @@ -11,9 +11,9 @@ import edu.wpi.first.math.Nat; import edu.wpi.first.math.VecBuilder; import org.junit.jupiter.api.Test; -public class AngleStatisticsTest { +class AngleStatisticsTest { @Test - public void testMean() { + void testMean() { // 3 states, 2 sigmas var sigmas = Matrix.mat(Nat.N3(), Nat.N2()).fill(1, 1.2, Math.toRadians(359), Math.toRadians(3), 1, 2); @@ -27,7 +27,7 @@ public class AngleStatisticsTest { } @Test - public void testResidual() { + void testResidual() { var first = VecBuilder.fill(1, Math.toRadians(1), 2); var second = VecBuilder.fill(1, Math.toRadians(359), 1); assertTrue( @@ -36,7 +36,7 @@ public class AngleStatisticsTest { } @Test - public void testAdd() { + void testAdd() { var first = VecBuilder.fill(1, Math.toRadians(1), 2); var second = VecBuilder.fill(1, Math.toRadians(359), 1); assertTrue(AngleStatistics.angleAdd(first, second, 1).isEqual(VecBuilder.fill(2, 0, 3), 1e-6)); diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java index 6e4b26140f..78908e48bb 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimatorTest.java @@ -21,10 +21,10 @@ import java.util.List; import java.util.Random; import org.junit.jupiter.api.Test; -public class DifferentialDrivePoseEstimatorTest { +class DifferentialDrivePoseEstimatorTest { @SuppressWarnings("LocalVariableName") @Test - public void testAccuracy() { + void testAccuracy() { var estimator = new DifferentialDrivePoseEstimator( new Rotation2d(), 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 18b095b4ef..5b07ebc941 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 @@ -27,8 +27,8 @@ import java.util.List; import org.junit.jupiter.api.Test; @SuppressWarnings("ParameterName") -public class ExtendedKalmanFilterTest { - public static Matrix getDynamics(final Matrix x, final Matrix u) { +class ExtendedKalmanFilterTest { + private static Matrix getDynamics(final Matrix x, final Matrix u) { final var motors = DCMotor.getCIM(2); final var gr = 7.08; // Gear ratio @@ -58,17 +58,19 @@ public class ExtendedKalmanFilterTest { return result; } - public static Matrix getLocalMeasurementModel(Matrix x, Matrix u) { + @SuppressWarnings("PMD.UnusedFormalParameter") + private static Matrix getLocalMeasurementModel(Matrix x, Matrix u) { return VecBuilder.fill(x.get(2, 0), x.get(3, 0), x.get(4, 0)); } - public static Matrix getGlobalMeasurementModel(Matrix x, Matrix u) { + @SuppressWarnings("PMD.UnusedFormalParameter") + private static Matrix getGlobalMeasurementModel(Matrix x, Matrix u) { return VecBuilder.fill(x.get(0, 0), x.get(1, 0), x.get(2, 0), x.get(3, 0), x.get(4, 0)); } @SuppressWarnings("LocalVariableName") @Test - public void testInit() { + void testInit() { double dtSeconds = 0.00505; assertDoesNotThrow( @@ -99,7 +101,7 @@ public class ExtendedKalmanFilterTest { @SuppressWarnings("LocalVariableName") @Test - public void testConvergence() { + void testConvergence() { double dtSeconds = 0.00505; double rbMeters = 0.8382 / 2.0; // Robot radius 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 0a18497a1f..4d709be7a5 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 @@ -25,7 +25,7 @@ import java.util.List; import java.util.Random; import org.junit.jupiter.api.Test; -public class KalmanFilterTest { +class KalmanFilterTest { private static LinearSystem elevatorPlant; private static final double kDt = 0.00505; @@ -35,7 +35,7 @@ public class KalmanFilterTest { } @SuppressWarnings("LocalVariableName") - public static void createElevator() { + private static void createElevator() { var motors = DCMotor.getVex775Pro(2); var m = 5.0; @@ -62,7 +62,7 @@ public class KalmanFilterTest { @Test @SuppressWarnings("LocalVariableName") - public void testElevatorKalmanFilter() { + void testElevatorKalmanFilter() { var Q = VecBuilder.fill(0.05, 1.0); var R = VecBuilder.fill(0.0001); @@ -70,7 +70,7 @@ public class KalmanFilterTest { } @Test - public void testSwerveKFStationary() { + void testSwerveKFStationary() { var random = new Random(); var filter = @@ -99,7 +99,7 @@ public class KalmanFilterTest { } @Test - public void testSwerveKFMovingWithoutAccelerating() { + void testSwerveKFMovingWithoutAccelerating() { var random = new Random(); var filter = @@ -137,7 +137,7 @@ public class KalmanFilterTest { @Test @SuppressWarnings("LocalVariableName") - public void testSwerveKFMovingOverTrajectory() { + void testSwerveKFMovingOverTrajectory() { var random = new Random(); var filter = diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java index 38b0d20a8b..d8756f0888 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimatorTest.java @@ -18,10 +18,10 @@ import java.util.List; import java.util.Random; import org.junit.jupiter.api.Test; -public class MecanumDrivePoseEstimatorTest { +class MecanumDrivePoseEstimatorTest { @Test @SuppressWarnings("LocalVariableName") - public void testAccuracy() { + void testAccuracy() { var kinematics = new MecanumDriveKinematics( new Translation2d(1, 1), new Translation2d(1, -1), diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java index b6e32fc56b..3c51d6c96a 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/MerweScaledSigmaPointsTest.java @@ -11,9 +11,9 @@ import edu.wpi.first.math.Nat; import edu.wpi.first.math.VecBuilder; import org.junit.jupiter.api.Test; -public class MerweScaledSigmaPointsTest { +class MerweScaledSigmaPointsTest { @Test - public void testZeroMeanPoints() { + void testZeroMeanPoints() { var merweScaledSigmaPoints = new MerweScaledSigmaPoints<>(Nat.N2()); var points = merweScaledSigmaPoints.sigmaPoints( @@ -28,7 +28,7 @@ public class MerweScaledSigmaPointsTest { } @Test - public void testNonzeroMeanPoints() { + void testNonzeroMeanPoints() { var merweScaledSigmaPoints = new MerweScaledSigmaPoints<>(Nat.N2()); var points = merweScaledSigmaPoints.sigmaPoints( diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java index 607e8de094..c6126c6f58 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java @@ -18,10 +18,10 @@ import java.util.List; import java.util.Random; import org.junit.jupiter.api.Test; -public class SwerveDrivePoseEstimatorTest { +class SwerveDrivePoseEstimatorTest { @Test @SuppressWarnings("LocalVariableName") - public void testAccuracy() { + void testAccuracy() { var kinematics = new SwerveDriveKinematics( new Translation2d(1, 1), 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 126459100e..25def496a0 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 @@ -29,9 +29,9 @@ import java.util.Arrays; import java.util.List; import org.junit.jupiter.api.Test; -public class UnscentedKalmanFilterTest { +class UnscentedKalmanFilterTest { @SuppressWarnings({"LocalVariableName", "ParameterName"}) - public static Matrix getDynamics(Matrix x, Matrix u) { + private static Matrix getDynamics(Matrix x, Matrix u) { var motors = DCMotor.getCIM(2); var gHigh = 7.08; @@ -69,19 +69,19 @@ public class UnscentedKalmanFilterTest { k2 * ((C1 * vl) + (C2 * Vl)) + k1 * ((C1 * vr) + (C2 * Vr))); } - @SuppressWarnings("ParameterName") - public static Matrix getLocalMeasurementModel(Matrix x, Matrix u) { + @SuppressWarnings({"PMD.UnusedFormalParameter", "ParameterName"}) + private static Matrix getLocalMeasurementModel(Matrix x, Matrix u) { return VecBuilder.fill(x.get(2, 0), x.get(3, 0), x.get(4, 0), x.get(5, 0)); } - @SuppressWarnings("ParameterName") - public static Matrix getGlobalMeasurementModel(Matrix x, Matrix u) { + @SuppressWarnings({"PMD.UnusedFormalParameter", "ParameterName"}) + private static Matrix getGlobalMeasurementModel(Matrix x, Matrix u) { return x.copy(); } @Test @SuppressWarnings("LocalVariableName") - public void testInit() { + void testInit() { assertDoesNotThrow( () -> { UnscentedKalmanFilter observer = @@ -104,7 +104,7 @@ public class UnscentedKalmanFilterTest { @SuppressWarnings("LocalVariableName") @Test - public void testConvergence() { + void testConvergence() { double dtSeconds = 0.00505; double rbMeters = 0.8382 / 2.0; // Robot radius @@ -206,7 +206,7 @@ public class UnscentedKalmanFilterTest { @Test @SuppressWarnings({"LocalVariableName", "ParameterName"}) - public void testLinearUKF() { + void testLinearUKF() { var dt = 0.020; var plant = LinearSystemId.identifyVelocitySystem(0.02, 0.006); var observer = @@ -236,7 +236,7 @@ public class UnscentedKalmanFilterTest { } @Test - public void testUnscentedTransform() { + void testUnscentedTransform() { // From FilterPy var ret = UnscentedKalmanFilter.unscentedTransform( diff --git a/wpimath/src/test/java/edu/wpi/first/math/filter/MedianFilterTest.java b/wpimath/src/test/java/edu/wpi/first/math/filter/MedianFilterTest.java index 06b3d019f0..1d6e00837c 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/filter/MedianFilterTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/filter/MedianFilterTest.java @@ -8,7 +8,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import org.junit.jupiter.api.Test; -public class MedianFilterTest { +class MedianFilterTest { @Test void medianFilterNotFullTestEven() { MedianFilter filter = new MedianFilter(10); diff --git a/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java b/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java index 9c1f2f3fce..f8921082c7 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/filter/SlewRateLimiterTest.java @@ -10,7 +10,7 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.util.WPIUtilJNI; import org.junit.jupiter.api.Test; -public class SlewRateLimiterTest { +class SlewRateLimiterTest { @Test void slewRateLimitTest() { WPIUtilJNI.enableMockTime(); diff --git a/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java b/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java index b6e66af400..5a314b131c 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/geometry/Pose2dTest.java @@ -53,6 +53,7 @@ class Pose2dTest { assertNotEquals(one, two); } + @Test void testMinus() { var initial = new Pose2d(0.0, 0.0, Rotation2d.fromDegrees(45.0)); var last = new Pose2d(5.0, 5.0, Rotation2d.fromDegrees(45.0)); diff --git a/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java b/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java index c13bb09709..69a4c8645a 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/geometry/Twist2dTest.java @@ -60,6 +60,7 @@ class Twist2dTest { assertNotEquals(one, two); } + @Test void testPose2dLog() { final var start = new Pose2d(); final var end = new Pose2d(5.0, 5.0, Rotation2d.fromDegrees(90.0)); diff --git a/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java b/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java index add1afb31f..3dff90b9be 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/system/DiscretizationTest.java @@ -14,11 +14,11 @@ import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.numbers.N2; import org.junit.jupiter.api.Test; -public class DiscretizationTest { +class DiscretizationTest { // Check that for a simple second-order system that we can easily analyze // analytically, @Test - public void testDiscretizeA() { + void testDiscretizeA() { final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, 0); final var x0 = VecBuilder.fill(1, 1); @@ -36,7 +36,7 @@ public class DiscretizationTest { // Check that for a simple second-order system that we can easily analyze // analytically, @Test - public void testDiscretizeAB() { + void testDiscretizeAB() { final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, 0); final var contB = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(0, 1); @@ -62,7 +62,7 @@ public class DiscretizationTest { // Test that the discrete approximation of Q ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ // 0 @Test - public void testDiscretizeSlowModelAQ() { + void testDiscretizeSlowModelAQ() { final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, 0); final var contQ = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(1, 0, 0, 1); @@ -91,7 +91,7 @@ public class DiscretizationTest { // Test that the discrete approximation of Q ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ // 0 @Test - public void testDiscretizeFastModelAQ() { + void testDiscretizeFastModelAQ() { final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, -1406.29); final var contQ = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0.0025, 0, 0, 1); @@ -118,7 +118,7 @@ public class DiscretizationTest { // Test that the Taylor series discretization produces nearly identical results. @Test - public void testDiscretizeSlowModelAQTaylor() { + void testDiscretizeSlowModelAQTaylor() { final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, 0); final var contQ = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(1, 0, 0, 1); @@ -161,7 +161,7 @@ public class DiscretizationTest { // Test that the Taylor series discretization produces nearly identical results. @Test - public void testDiscretizeFastModelAQTaylor() { + void testDiscretizeFastModelAQTaylor() { final var contA = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0, 1, 0, -1500); final var contQ = new MatBuilder<>(Nat.N2(), Nat.N2()).fill(0.0025, 0, 0, 1); @@ -204,7 +204,7 @@ public class DiscretizationTest { // Test that DiscretizeR() works @Test - public void testDiscretizeR() { + void testDiscretizeR() { var contR = Matrix.mat(Nat.N2(), Nat.N2()).fill(2.0, 0.0, 0.0, 1.0); var discRTruth = Matrix.mat(Nat.N2(), Nat.N2()).fill(4.0, 0.0, 0.0, 2.0); diff --git a/wpimath/src/test/java/edu/wpi/first/math/system/LinearSystemIDTest.java b/wpimath/src/test/java/edu/wpi/first/math/system/LinearSystemIDTest.java index 37cb1ecc99..a9f5b09367 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/system/LinearSystemIDTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/system/LinearSystemIDTest.java @@ -16,7 +16,7 @@ import org.junit.jupiter.api.Test; class LinearSystemIDTest { @Test - public void testDrivetrainVelocitySystem() { + void testDrivetrainVelocitySystem() { var model = LinearSystemId.createDrivetrainVelocitySystem(DCMotor.getNEO(4), 70, 0.05, 0.4, 6.0, 6); assertTrue( @@ -40,7 +40,7 @@ class LinearSystemIDTest { } @Test - public void testElevatorSystem() { + void testElevatorSystem() { var model = LinearSystemId.createElevatorSystem(DCMotor.getNEO(2), 5, 0.05, 12); assertTrue( model.getA().isEqual(Matrix.mat(Nat.N2(), Nat.N2()).fill(0, 1, 0, -99.05473), 0.001)); @@ -53,7 +53,7 @@ class LinearSystemIDTest { } @Test - public void testFlywheelSystem() { + void testFlywheelSystem() { var model = LinearSystemId.createFlywheelSystem(DCMotor.getNEO(2), 0.00032, 1.0); assertTrue(model.getA().isEqual(VecBuilder.fill(-26.87032), 0.001)); @@ -65,7 +65,7 @@ class LinearSystemIDTest { } @Test - public void testIdentifyPositionSystem() { + void testIdentifyPositionSystem() { // By controls engineering in frc, // x-dot = [0 1 | 0 -kv/ka] x = [0 | 1/ka] u var kv = 1.0; @@ -77,7 +77,7 @@ class LinearSystemIDTest { } @Test - public void testIdentifyVelocitySystem() { + void testIdentifyVelocitySystem() { // By controls engineering in frc, // V = kv * velocity + ka * acceleration // x-dot = -kv/ka * v + 1/ka \cdot V diff --git a/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java b/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java index b3fe7e6479..6671963077 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/system/NumericalIntegrationTest.java @@ -12,9 +12,9 @@ import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.numbers.N1; import org.junit.jupiter.api.Test; -public class NumericalIntegrationTest { +class NumericalIntegrationTest { @Test - public void testExponential() { + void testExponential() { Matrix y0 = VecBuilder.fill(0.0); var y1 = @@ -31,7 +31,7 @@ public class NumericalIntegrationTest { } @Test - public void testExponentialRKF45() { + void testExponentialRKF45() { Matrix y0 = VecBuilder.fill(0.0); var y1 = @@ -49,7 +49,7 @@ public class NumericalIntegrationTest { } @Test - public void testExponentialRKDP() { + void testExponentialRKDP() { Matrix y0 = VecBuilder.fill(0.0); var y1 = diff --git a/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java b/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java index ee843ab4fc..e4df93f975 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/system/RungeKuttaTimeVaryingTest.java @@ -12,7 +12,7 @@ import edu.wpi.first.math.Nat; import edu.wpi.first.math.numbers.N1; import org.junit.jupiter.api.Test; -public class RungeKuttaTimeVaryingTest { +class RungeKuttaTimeVaryingTest { private static Matrix rungeKuttaTimeVaryingSolution(double t) { return new MatBuilder<>(Nat.N1(), Nat.N1()) .fill(12.0 * Math.exp(t) / (Math.pow(Math.exp(t) + 1.0, 2.0))); @@ -26,7 +26,7 @@ public class RungeKuttaTimeVaryingTest { // // x(t) = 12 * e^t / ((e^t + 1)^2) @Test - public void rungeKuttaTimeVaryingTest() { + void rungeKuttaTimeVaryingTest() { final var y0 = rungeKuttaTimeVaryingSolution(5.0); final var y1 = diff --git a/wpimath/src/test/java/edu/wpi/first/math/trajectory/EllipticalRegionConstraintTest.java b/wpimath/src/test/java/edu/wpi/first/math/trajectory/EllipticalRegionConstraintTest.java index f9e3c1821f..039b3f7983 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/trajectory/EllipticalRegionConstraintTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/trajectory/EllipticalRegionConstraintTest.java @@ -16,7 +16,7 @@ import edu.wpi.first.math.util.Units; import java.util.List; import org.junit.jupiter.api.Test; -public class EllipticalRegionConstraintTest { +class EllipticalRegionConstraintTest { @Test void testConstraint() { // Create constraints diff --git a/wpimath/src/test/java/edu/wpi/first/math/trajectory/RectangularRegionConstraintTest.java b/wpimath/src/test/java/edu/wpi/first/math/trajectory/RectangularRegionConstraintTest.java index 1ab826edea..390a6c2841 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/trajectory/RectangularRegionConstraintTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/trajectory/RectangularRegionConstraintTest.java @@ -16,7 +16,7 @@ import edu.wpi.first.math.util.Units; import java.util.List; import org.junit.jupiter.api.Test; -public class RectangularRegionConstraintTest { +class RectangularRegionConstraintTest { @Test void testConstraint() { // Create constraints diff --git a/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryJsonTest.java b/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryJsonTest.java index bb7260110d..1d3c4303bb 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryJsonTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrajectoryJsonTest.java @@ -12,7 +12,7 @@ import edu.wpi.first.math.trajectory.constraint.DifferentialDriveKinematicsConst import java.util.List; import org.junit.jupiter.api.Test; -public class TrajectoryJsonTest { +class TrajectoryJsonTest { @Test void deserializeMatches() { var config = diff --git a/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrapezoidProfileTest.java b/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrapezoidProfileTest.java index 062563fcdb..ee6cc8ffb8 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrapezoidProfileTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/trajectory/TrapezoidProfileTest.java @@ -201,7 +201,7 @@ class TrapezoidProfileTest { for (int i = 0; i < 400; i++) { profile = new TrapezoidProfile(constraints, goal, state); state = profile.calculate(kDt); - if (!reachedGoal && (Math.abs(state.velocity - 1) < 10e-5)) { + if (!reachedGoal && Math.abs(state.velocity - 1) < 10e-5) { assertNear(predictedTimeLeft, i / 100.0, 2e-2); reachedGoal = true; } @@ -244,7 +244,7 @@ class TrapezoidProfileTest { for (int i = 0; i < 400; i++) { profile = new TrapezoidProfile(constraints, goal, state); state = profile.calculate(kDt); - if (!reachedGoal && (Math.abs(state.velocity + 1) < 10e-5)) { + if (!reachedGoal && Math.abs(state.velocity + 1) < 10e-5) { assertNear(predictedTimeLeft, i / 100.0, 2e-2); reachedGoal = true; } diff --git a/wpimath/src/test/java/edu/wpi/first/math/util/UnitsTest.java b/wpimath/src/test/java/edu/wpi/first/math/util/UnitsTest.java index 99a8b5aa10..06c2bc7e8c 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/util/UnitsTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/util/UnitsTest.java @@ -64,6 +64,7 @@ class UnitsTest extends UtilityClassTest { assertEquals(1500, Units.secondsToMilliseconds(1.5), 1e-2); } + @Test void kilogramsToLbsTest() { assertEquals(2.20462, Units.kilogramsToLbs(1), 1e-2); } diff --git a/wpimath/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java b/wpimath/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java index 8eed93f9ba..0501f6d8b0 100644 --- a/wpimath/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java +++ b/wpimath/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java @@ -34,19 +34,20 @@ public abstract class UtilityClassTest { } @Test - public void singleConstructorTest() { + void singleConstructorTest() { assertEquals(1, m_clazz.getDeclaredConstructors().length, "More than one constructor defined"); } @Test - public void constructorPrivateTest() { + void constructorPrivateTest() { Constructor constructor = m_clazz.getDeclaredConstructors()[0]; assertFalse(constructor.canAccess(null), "Constructor is not private"); } @Test - public void constructorReflectionTest() { + @SuppressWarnings("PMD.AvoidAccessibilityAlteration") + void constructorReflectionTest() { Constructor constructor = m_clazz.getDeclaredConstructors()[0]; constructor.setAccessible(true); assertThrows(InvocationTargetException.class, constructor::newInstance); diff --git a/wpiutil/CMakeLists.txt b/wpiutil/CMakeLists.txt index a5871bcf50..a30177299e 100644 --- a/wpiutil/CMakeLists.txt +++ b/wpiutil/CMakeLists.txt @@ -14,18 +14,18 @@ if (WITH_JAVA) include(UseJava) set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked") - if(NOT EXISTS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/jackson-core-2.10.0.jar") + if(NOT EXISTS "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson/jackson-core-2.12.4.jar") set(BASE_URL "https://search.maven.org/remotecontent?filepath=") set(JAR_ROOT "${WPILIB_BINARY_DIR}/wpiutil/thirdparty/jackson") message(STATUS "Downloading Jackson jarfiles...") - file(DOWNLOAD "${BASE_URL}com/fasterxml/jackson/core/jackson-core/2.10.0/jackson-core-2.10.0.jar" - "${JAR_ROOT}/jackson-core-2.10.0.jar") - file(DOWNLOAD "${BASE_URL}com/fasterxml/jackson/core/jackson-databind/2.10.0/jackson-databind-2.10.0.jar" - "${JAR_ROOT}/jackson-databind-2.10.0.jar") - file(DOWNLOAD "${BASE_URL}com/fasterxml/jackson/core/jackson-annotations/2.10.0/jackson-annotations-2.10.0.jar" - "${JAR_ROOT}/jackson-annotations-2.10.0.jar") + file(DOWNLOAD "${BASE_URL}com/fasterxml/jackson/core/jackson-core/2.12.4/jackson-core-2.12.4.jar" + "${JAR_ROOT}/jackson-core-2.12.4.jar") + file(DOWNLOAD "${BASE_URL}com/fasterxml/jackson/core/jackson-databind/2.12.4/jackson-databind-2.12.4.jar" + "${JAR_ROOT}/jackson-databind-2.12.4.jar") + file(DOWNLOAD "${BASE_URL}com/fasterxml/jackson/core/jackson-annotations/2.12.4/jackson-annotations-2.12.4.jar" + "${JAR_ROOT}/jackson-annotations-2.12.4.jar") message(STATUS "All files downloaded.") endif() diff --git a/wpiutil/build.gradle b/wpiutil/build.gradle index 46fe6e6e61..31687233d5 100644 --- a/wpiutil/build.gradle +++ b/wpiutil/build.gradle @@ -294,7 +294,7 @@ model { } dependencies { - api "com.fasterxml.jackson.core:jackson-annotations:2.10.0" - api "com.fasterxml.jackson.core:jackson-core:2.10.0" - api "com.fasterxml.jackson.core:jackson-databind:2.10.0" + api "com.fasterxml.jackson.core:jackson-annotations:2.12.4" + api "com.fasterxml.jackson.core:jackson-core:2.12.4" + api "com.fasterxml.jackson.core:jackson-databind:2.12.4" } 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 320bc5bec5..d4ad833042 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/RuntimeDetector.java @@ -150,7 +150,7 @@ public final class RuntimeDetector { * @return if architecture is aarch64 */ public static boolean isAarch64() { - return System.getProperty("os.arch").equals("aarch64"); + return "aarch64".equals(System.getProperty("os.arch")); } public static boolean isLinux() { 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 8a2c11af4d..942055a94d 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/RuntimeLoader.java @@ -140,12 +140,12 @@ public final class RuntimeLoader { } catch (UnsatisfiedLinkError ule) { // Then load the hash from the input file String resname = RuntimeDetector.getLibraryResource(m_libraryName); - String hash = null; + String hash; try (InputStream is = m_loadClass.getResourceAsStream(resname)) { if (is == null) { throw new IOException(getLoadErrorMessage(ule)); } - MessageDigest md = null; + MessageDigest md; try { md = MessageDigest.getInstance("MD5"); } catch (NoSuchAlgorithmException nsae) { diff --git a/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java b/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java index 9d919afb68..2a4c2c9bdb 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/sendable/SendableRegistry.java @@ -462,7 +462,7 @@ public class SendableRegistry { * @param dataHandle data handle to get data object passed to callback * @param callback function to call for each object */ - @SuppressWarnings("PMD.AvoidCatchingThrowable") + @SuppressWarnings({"PMD.AvoidCatchingThrowable", "PMD.AvoidReassigningCatchVariables"}) public static synchronized void foreachLiveWindow( int dataHandle, Consumer callback) { CallbackData cbdata = new CallbackData();