diff --git a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java index 5ce6334e32..3d9e119406 100644 --- a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java +++ b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java @@ -18,7 +18,6 @@ public final class CameraServerSharedStore { if (cameraServerShared == null) { cameraServerShared = new CameraServerShared() { - @Override public void reportVideoServer(int id) {} diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java index c5466a542e..8f9901bfc5 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java @@ -16,7 +16,6 @@ import java.util.function.BooleanSupplier; * specified explicitly from the command implementation. */ public interface Command { - /** The initial subroutine of a command. Called once when the command is initially scheduled. */ default void initialize() {} diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java index 9a55ffd13a..bb1df60fd4 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java @@ -12,7 +12,6 @@ import java.util.Set; /** A {@link Sendable} base class for {@link Command}s. */ public abstract class CommandBase implements Sendable, Command { - protected Set m_requirements = new HashSet<>(); protected CommandBase() { diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java index 69306afac3..28c75a9b1e 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java @@ -194,7 +194,6 @@ public class MecanumControllerCommand extends CommandBase { Supplier currentWheelSpeeds, Consumer outputDriveVoltages, Subsystem... requirements) { - this( trajectory, pose, diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java index 09ef1c86f4..4e28b16e37 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java @@ -20,7 +20,6 @@ package edu.wpi.first.wpilibj2.command; * base for user implementations that handles this. */ public interface Subsystem { - /** * This method is called periodically by the {@link CommandScheduler}. Useful for updating * subsystem-specific state that you don't want to offload to a {@link Command}. Teams should try diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java index 7dc62674ca..c6858034a3 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java @@ -13,7 +13,6 @@ import edu.wpi.first.util.sendable.SendableRegistry; * method for setting the default command. */ public abstract class SubsystemBase implements Subsystem, Sendable { - /** Constructor. */ public SubsystemBase() { String name = this.getClass().getSimpleName(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java index c3136db69f..da784736fc 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandGroupErrorTest.java @@ -12,7 +12,6 @@ import org.junit.jupiter.api.Test; class CommandGroupErrorTest extends CommandTestBase { @Test void commandInMultipleGroupsTest() { - MockCommandHolder command1Holder = new MockCommandHolder(true); Command command1 = command1Holder.getMock(); MockCommandHolder command2Holder = new MockCommandHolder(true); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java index 0047740e76..c4ba8275b9 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/ButtonTest.java @@ -135,7 +135,6 @@ class ButtonTest extends CommandTestBase { @Test void runnableBindingTest() { - InternalButton buttonWhenPressed = new InternalButton(); InternalButton buttonWhileHeld = new InternalButton(); InternalButton buttonWhenReleased = new InternalButton(); 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 c9ae390732..958be43ca2 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -40,7 +40,6 @@ public class DoubleSolenoid implements Sendable, AutoCloseable { * @param reverseChannel The reverse channel on the module to control (0..7). */ public DoubleSolenoid(PneumaticsBase module, final int forwardChannel, final int reverseChannel) { - m_module = Objects.requireNonNull(module, "Module cannot be null"); // TODO check channels diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java index 212dd0e420..03f92ba66c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PneumaticsBase.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj; public interface PneumaticsBase extends AutoCloseable { - /** * Sets solenoids on a pneumatics module. * 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 e41dfe41b4..96f55b6d32 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -41,7 +41,6 @@ public abstract class RobotBase implements AutoCloseable { private static void setupCameraServerShared() { CameraServerShared shared = new CameraServerShared() { - @Override public void reportVideoServer(int id) { HAL.report(tResourceType.kResourceType_PCVideoServer, id + 1); 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 7495534e5e..8b4e009066 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 @@ -14,7 +14,6 @@ import java.util.function.Supplier; /** Common interface for objects that can contain shuffleboard components. */ public interface ShuffleboardContainer extends ShuffleboardValue { - /** * Gets the components that are direct children of this container. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardRoot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardRoot.java index cbeecd4ce9..fa6cd08deb 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardRoot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardRoot.java @@ -11,7 +11,6 @@ package edu.wpi.first.wpilibj.shuffleboard; *

This class is package-private to minimize API surface area. */ interface ShuffleboardRoot { - /** * Gets the tab with the given title, creating it if it does not already exist. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardValue.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardValue.java index 9d77a0a98d..88f4389672 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardValue.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardValue.java @@ -7,7 +7,6 @@ package edu.wpi.first.wpilibj.shuffleboard; import edu.wpi.first.networktables.NetworkTable; interface ShuffleboardValue { - /** * Gets the title of this Shuffleboard value. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardWidget.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardWidget.java index fa548dfc29..39ce03613e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardWidget.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardWidget.java @@ -13,7 +13,6 @@ package edu.wpi.first.wpilibj.shuffleboard; */ abstract class ShuffleboardWidget> extends ShuffleboardComponent { - ShuffleboardWidget(ShuffleboardContainer parent, String title) { super(parent, title); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java index 9556710035..0a9e59dff6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DifferentialDrivetrainSim.java @@ -155,7 +155,6 @@ public class DifferentialDrivetrainSim { */ @SuppressWarnings("LocalVariableName") public void update(double dtSeconds) { - // Update state estimate with RK4 m_x = NumericalIntegration.rk4(this::getDynamics, m_x, m_u, dtSeconds); m_y = m_x; @@ -319,7 +318,6 @@ public class DifferentialDrivetrainSim { @SuppressWarnings({"DuplicatedCode", "LocalVariableName", "ParameterName"}) protected Matrix getDynamics(Matrix x, Matrix u) { - // Because G can be factored out of B, we can divide by the old ratio and multiply // by the new ratio to get a new drivetrain model. var B = new Matrix<>(Nat.N4(), Nat.N2()); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java index c37dfaf9a1..855ace54e2 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java @@ -16,7 +16,6 @@ import org.junit.jupiter.api.Test; class MatchInfoDataTest { @Test void testSetMatchInfo() { - MatchType matchType = MatchType.Qualification; DriverStationDataJNI.setMatchInfo("Event Name", "Game Message", 174, 191, matchType.ordinal()); 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 2be9e01952..b0399237eb 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 @@ -21,7 +21,6 @@ public class ElevatorSimTest { @Test @SuppressWarnings({"LocalVariableName", "resource"}) public void testStateSpaceSimWithElevator() { - var controller = new PIDController(10, 0, 0); var sim = diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java index 084589414a..95183d7398 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java @@ -55,7 +55,6 @@ public class RobotContainer { * JoystickButton}. */ private void configureButtonBindings() { - // Move the arm to 2 radians above horizontal when the 'A' button is pressed. new JoystickButton(m_driverController, Button.kA.value) .whenPressed( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java index ca6a3a5f08..e8d8a163f2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java @@ -55,7 +55,6 @@ public class RobotContainer { * JoystickButton}. */ private void configureButtonBindings() { - // Move the arm to 2 radians above horizontal when the 'A' button is pressed. new JoystickButton(m_driverController, Button.kA.value) .whenPressed(() -> m_robotArm.setGoal(2), m_robotArm); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java index e9995a1771..a1582d96d9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java @@ -78,7 +78,6 @@ public class RobotContainer { * @return the command to run in autonomous */ public Command getAutonomousCommand() { - // Create a voltage constraint to ensure we don't accelerate too fast var autoVoltageConstraint = new DifferentialDriveVoltageConstraint( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java index baecb65bf2..0cd83a925e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java @@ -55,7 +55,6 @@ public class Robot extends TimedRobot { /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ @Override public void autonomousInit() { - // Get selected routine from the SmartDashboard m_autonomousCommand = m_robotContainer.getAutonomousCommand(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java index 01694ae2e5..015a9da878 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java @@ -84,7 +84,6 @@ public class RobotContainer { * @return the command to run in autonomous */ public Command getAutonomousCommand() { - // Create a voltage constraint to ensure we don't accelerate too fast var autoVoltageConstraint = new DifferentialDriveVoltageConstraint( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java index 538f3f7484..26ee8f702a 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java @@ -91,7 +91,6 @@ public class Robot extends TimedRobot { @Override public void teleopPeriodic() { - // Sets the target speed of our flywheel. This is similar to setting the setpoint of a // PID controller. if (m_joystick.getTriggerPressed()) { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java index 6bf039ae25..fd4c0b702d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java @@ -46,7 +46,6 @@ public class SwerveModule { int[] turningEncoderPorts, boolean driveEncoderReversed, boolean turningEncoderReversed) { - m_driveMotor = new Spark(driveMotorChannel); m_turningMotor = new Spark(turningMotorChannel); diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java index e9d8d84d8d..219a611a26 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java @@ -97,7 +97,6 @@ public abstract class AbstractInterruptTest extends AbstractComsSetup { @Test(timeout = 2000) public void testMultipleInterruptsTriggering() { - AtomicBoolean hasFired = new AtomicBoolean(false); AtomicInteger counter = new AtomicInteger(0); @@ -130,7 +129,6 @@ public abstract class AbstractInterruptTest extends AbstractComsSetup { @Test(timeout = (long) (synchronousTimeout * 1e3)) public void testSynchronousInterruptsTriggering() { - try (SynchronousInterrupt interrupt = new SynchronousInterrupt(getSource())) { final double synchronousDelay = synchronousTimeout / 2.0; final Runnable runnable = @@ -176,7 +174,6 @@ public abstract class AbstractInterruptTest extends AbstractComsSetup { @Test(timeout = (long) (synchronousTimeout * 1e3)) public void testSynchronousInterruptsWaitResultRisingEdge() { try (SynchronousInterrupt interrupt = new SynchronousInterrupt(getSource())) { - final double synchronousDelay = synchronousTimeout / 2.0; final Runnable runnable = () -> { diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java index 96a69a4347..c71ca6bf0c 100644 --- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java +++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java @@ -157,7 +157,6 @@ public final class TestBench { * @return a freshly allocated Servo's and a freshly allocated Gyroscope */ public static TiltPanCameraFixture getTiltPanCam() { - return new TiltPanCameraFixture() { @Override protected AnalogGyro giveGyro() { diff --git a/wpimath/src/main/java/edu/wpi/first/math/Vector.java b/wpimath/src/main/java/edu/wpi/first/math/Vector.java index b2d989a039..9b06e71402 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/Vector.java +++ b/wpimath/src/main/java/edu/wpi/first/math/Vector.java @@ -15,7 +15,6 @@ import org.ejml.simple.SimpleMatrix; * @param The number of rows in this matrix. */ public class Vector extends Matrix { - /** * Constructs an empty zero vector of the given dimensions. * diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java index daaadb457c..fb0628b2f2 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/MerweScaledSigmaPoints.java @@ -23,7 +23,6 @@ import org.ejml.simple.SimpleMatrix; * State-Space Models" (Doctoral dissertation) */ public class MerweScaledSigmaPoints { - private final double m_alpha; private final int m_kappa; private final Nat m_states; diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java index ec163a0e8d..6b48be10a3 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java @@ -29,7 +29,6 @@ import org.ejml.simple.SimpleMatrix; @SuppressWarnings({"MemberName", "ClassTypeParameterName"}) public class UnscentedKalmanFilter implements KalmanTypeFilter { - private final Nat m_states; private final Nat m_outputs; diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java index 81393763b6..7fc6ca4860 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/SwerveModuleState.java @@ -9,7 +9,6 @@ import edu.wpi.first.math.geometry.Rotation2d; /** Represents the state of one swerve module. */ @SuppressWarnings("MemberName") public class SwerveModuleState implements Comparable { - /** Speed of the wheel of the module. */ public double speedMetersPerSecond; diff --git a/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java b/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java index c68e4e2598..e5c67f84b9 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java +++ b/wpimath/src/main/java/edu/wpi/first/math/spline/SplineHelper.java @@ -81,7 +81,6 @@ public final class SplineHelper { @SuppressWarnings("LocalVariableName") public static CubicHermiteSpline[] getCubicSplinesFromControlVectors( Spline.ControlVector start, Translation2d[] waypoints, Spline.ControlVector end) { - CubicHermiteSpline[] splines = new CubicHermiteSpline[waypoints.length + 1]; double[] xInitial = start.x; diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java b/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java index 30e3a52ecd..6089d1cb3e 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystem.java @@ -11,7 +11,6 @@ import edu.wpi.first.math.numbers.N1; @SuppressWarnings("ClassTypeParameterName") public class LinearSystem { - /** Continuous system matrix. */ @SuppressWarnings("MemberName") private final Matrix m_A; @@ -42,7 +41,6 @@ public class LinearSystem b, Matrix c, Matrix d) { - this.m_A = a; this.m_B = b; this.m_C = c; diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java b/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java index 164f5fa668..8f3da6aab6 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java @@ -30,7 +30,6 @@ import org.ejml.simple.SimpleMatrix; */ @SuppressWarnings("ClassTypeParameterName") public class LinearSystemLoop { - private final LinearQuadraticRegulator m_controller; private final LinearPlantInversionFeedforward m_feedforward; private final KalmanFilter m_observer; diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java b/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java index 608c2f6e22..1d74ba2cdd 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/NumericalIntegration.java @@ -75,7 +75,6 @@ public final class NumericalIntegration { Matrix x, Matrix u, double dtSeconds) { - final var halfDt = 0.5 * dtSeconds; Matrix k1 = f.apply(x, u); Matrix k2 = f.apply(x.plus(k1.times(halfDt)), u); @@ -96,7 +95,6 @@ public final class NumericalIntegration { @SuppressWarnings({"ParameterName", "MethodTypeParameterName"}) public static Matrix rk4( Function, Matrix> f, Matrix x, double dtSeconds) { - final var halfDt = 0.5 * dtSeconds; Matrix k1 = f.apply(x); Matrix k2 = f.apply(x.plus(k1.times(halfDt))); @@ -147,7 +145,6 @@ public final class NumericalIntegration { Matrix u, double dtSeconds, double maxError) { - double dtElapsed = 0; double previousH = dtSeconds; // Loop until we've gotten to our desired dt @@ -224,7 +221,6 @@ public final class NumericalIntegration { double initialH, double maxTruncationError, double dtRemaining) { - double truncationErr; double h = initialH; Matrix newX; diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java b/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java index 12e0b0fbea..c49bb6f2ff 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/plant/LinearSystemId.java @@ -195,7 +195,6 @@ public final class LinearSystemId { @SuppressWarnings("ParameterName") public static LinearSystem identifyDrivetrainSystem( double kVLinear, double kALinear, double kVAngular, double kAAngular) { - final double A1 = 0.5 * -(kVLinear / kALinear + kVAngular / kAAngular); final double A2 = 0.5 * -(kVLinear / kALinear - kVAngular / kAAngular); final double B1 = 0.5 * (1.0 / kALinear + 1.0 / kAAngular); diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java index 7d0004bd00..d7fbf599d8 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrajectoryParameterizer.java @@ -260,7 +260,6 @@ public final class TrajectoryParameterizer { private static void enforceAccelerationLimits( boolean reverse, List constraints, ConstrainedState state) { - for (final var constraint : constraints) { double factor = reverse ? -1.0 : 1.0; final var minMaxAccel = diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java index 9776a3c436..4c7e81448e 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/DifferentialDriveVoltageConstraint.java @@ -51,7 +51,6 @@ public class DifferentialDriveVoltageConstraint implements TrajectoryConstraint @Override public MinMax getMinMaxAccelerationMetersPerSecondSq( Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond) { - var wheelSpeeds = m_kinematics.toWheelSpeeds( new ChassisSpeeds( diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java index ed03a3185a..bbf30f788f 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/constraint/TrajectoryConstraint.java @@ -11,7 +11,6 @@ import edu.wpi.first.math.geometry.Pose2d; * trajectories. */ public interface TrajectoryConstraint { - /** * Returns the max velocity given the current pose and curvature. * 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 5658709382..ddd834237b 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 @@ -48,7 +48,6 @@ public class LinearQuadraticRegulatorTest { @Test @SuppressWarnings("LocalVariableName") public void testLQROnElevator() { - var qElms = VecBuilder.fill(0.02, 0.4); var rElms = VecBuilder.fill(12.0); var dt = 0.00505; @@ -63,7 +62,6 @@ public class LinearQuadraticRegulatorTest { @Test public void testFourMotorElevator() { - var dt = 0.020; var plant = @@ -80,7 +78,6 @@ public class LinearQuadraticRegulatorTest { @Test @SuppressWarnings("LocalVariableName") public void testLQROnArm() { - var motors = DCMotor.getVex775Pro(2); var m = 4.0; 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 e4cd694cac..857c47706d 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 @@ -54,7 +54,6 @@ public class LinearSystemLoopTest { @Test @SuppressWarnings("LocalVariableName") public void testStateSpaceEnabled() { - m_loop.reset(VecBuilder.fill(0, 0)); Matrix references = VecBuilder.fill(2.0, 0.0); var constraints = new TrapezoidProfile.Constraints(4, 3); @@ -84,7 +83,6 @@ public class LinearSystemLoopTest { @Test @SuppressWarnings("LocalVariableName") public void testFlywheelEnabled() { - LinearSystem plant = LinearSystemId.createFlywheelSystem(DCMotor.getNEO(2), 0.00289, 1.0); KalmanFilter observer = @@ -113,7 +111,6 @@ public class LinearSystemLoopTest { var time = 0.0; while (time < 10) { - if (time > 10) { break; } 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 70da6d9c45..8cc18b2a34 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 @@ -64,7 +64,6 @@ public class KalmanFilterTest { @Test @SuppressWarnings("LocalVariableName") public void testElevatorKalmanFilter() { - var Q = VecBuilder.fill(0.05, 1.0); var R = VecBuilder.fill(0.0001); @@ -73,7 +72,6 @@ public class KalmanFilterTest { @Test public void testSwerveKFStationary() { - var random = new Random(); var filter = @@ -121,7 +119,6 @@ public class KalmanFilterTest { @Test public void testSwerveKFMovingWithoutAccelerating() { - var random = new Random(); var filter = @@ -178,7 +175,6 @@ public class KalmanFilterTest { @Test @SuppressWarnings("LocalVariableName") public void testSwerveKFMovingOverTrajectory() { - var random = new Random(); var filter = 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 7dfca748f9..00a6565c4a 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 @@ -171,7 +171,6 @@ public class UnscentedKalmanFilterTest { double totalTime = trajectory.getTotalTimeSeconds(); for (int i = 0; i < (totalTime / dtSeconds); i++) { - ref = trajectory.sample(dtSeconds * i); double vl = ref.velocityMetersPerSecond * (1 - (ref.curvatureRadPerMeter * rbMeters)); double vr = ref.velocityMetersPerSecond * (1 + (ref.curvatureRadPerMeter * rbMeters)); diff --git a/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java b/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java index 9345bf8515..d3346799c2 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveKinematicsTest.java @@ -35,7 +35,6 @@ class MecanumDriveKinematicsTest { @Test void testStraightLineForwardKinematicsKinematics() { - var wheelSpeeds = new MecanumDriveWheelSpeeds(3.536, 3.536, 3.536, 3.536); var moduleStates = m_kinematics.toChassisSpeeds(wheelSpeeds); @@ -59,7 +58,6 @@ class MecanumDriveKinematicsTest { @Test void testStrafeForwardKinematicsKinematics() { - var wheelSpeeds = new MecanumDriveWheelSpeeds(-2.828427, 2.828427, 2.828427, -2.828427); var moduleStates = m_kinematics.toChassisSpeeds(wheelSpeeds); @@ -152,7 +150,6 @@ class MecanumDriveKinematicsTest { @Test void testOffCenterRotationTranslationForwardKinematicsKinematics() { - var wheelSpeeds = new MecanumDriveWheelSpeeds(2.12, 21.92, -12.02, 36.06); var moduleStates = m_kinematics.toChassisSpeeds(wheelSpeeds); diff --git a/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java b/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java index fb81b6da44..eec6aa2111 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveKinematicsTest.java @@ -52,7 +52,6 @@ class SwerveDriveKinematicsTest { @Test void testStraightStrafeInverseKinematics() { - ChassisSpeeds speeds = new ChassisSpeeds(0, 5, 0); var moduleStates = m_kinematics.toSwerveModuleStates(speeds); @@ -80,7 +79,6 @@ class SwerveDriveKinematicsTest { @Test void testTurnInPlaceInverseKinematics() { - ChassisSpeeds speeds = new ChassisSpeeds(0, 0, 2 * Math.PI); var moduleStates = m_kinematics.toSwerveModuleStates(speeds); @@ -119,7 +117,6 @@ class SwerveDriveKinematicsTest { @Test void testOffCenterCORRotationInverseKinematics() { - ChassisSpeeds speeds = new ChassisSpeeds(0, 0, 2 * Math.PI); var moduleStates = m_kinematics.toSwerveModuleStates(speeds, m_fl); @@ -188,7 +185,6 @@ class SwerveDriveKinematicsTest { */ @Test void testOffCenterCORRotationAndTranslationInverseKinematics() { - ChassisSpeeds speeds = new ChassisSpeeds(0.0, 3.0, 1.5); var moduleStates = m_kinematics.toSwerveModuleStates(speeds, new Translation2d(24, 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 353d066b20..37cb1ecc99 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 @@ -41,7 +41,6 @@ class LinearSystemIDTest { @Test public 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)); 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 3dc9b49619..b7cfbd18ea 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 @@ -16,7 +16,6 @@ public class NumericalIntegrationTest { @Test @SuppressWarnings({"ParameterName", "LocalVariableName"}) public void testExponential() { - Matrix y0 = VecBuilder.fill(0.0); //noinspection SuspiciousNameCombination @@ -36,7 +35,6 @@ public class NumericalIntegrationTest { @Test @SuppressWarnings({"ParameterName", "LocalVariableName"}) public void testExponentialAdaptive() { - Matrix y0 = VecBuilder.fill(0.0); //noinspection SuspiciousNameCombination