diff --git a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java index ce2336c6b1..c4b1eb8de8 100644 --- a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java +++ b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFieldLayout.java @@ -143,7 +143,7 @@ public class AprilTagFieldLayout { * @param origin The predefined origin */ @JsonIgnore - public void setOrigin(OriginPosition origin) { + public final void setOrigin(OriginPosition origin) { switch (origin) { case kBlueAllianceWallRightSide: setOrigin(new Pose3d()); @@ -168,7 +168,7 @@ public class AprilTagFieldLayout { * @param origin The new origin for tag transformations */ @JsonIgnore - public void setOrigin(Pose3d origin) { + public final void setOrigin(Pose3d origin) { m_origin = origin; } diff --git a/cameraserver/src/main/java/edu/wpi/first/vision/VisionThread.java b/cameraserver/src/main/java/edu/wpi/first/vision/VisionThread.java index 6f1a1e35b5..93d4e83758 100644 --- a/cameraserver/src/main/java/edu/wpi/first/vision/VisionThread.java +++ b/cameraserver/src/main/java/edu/wpi/first/vision/VisionThread.java @@ -21,6 +21,7 @@ public class VisionThread extends Thread { * * @param visionRunner the runner for a vision pipeline */ + @SuppressWarnings("this-escape") public VisionThread(VisionRunner visionRunner) { super(visionRunner::runForever, "WPILib Vision Thread"); setDaemon(true); diff --git a/romiVendordep/src/main/java/edu/wpi/first/wpilibj/romi/RomiMotor.java b/romiVendordep/src/main/java/edu/wpi/first/wpilibj/romi/RomiMotor.java index 93024f6a2c..1a56bf78bc 100644 --- a/romiVendordep/src/main/java/edu/wpi/first/wpilibj/romi/RomiMotor.java +++ b/romiVendordep/src/main/java/edu/wpi/first/wpilibj/romi/RomiMotor.java @@ -14,7 +14,7 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMMotorController; */ public class RomiMotor extends PWMMotorController { /** Common initialization code called by all constructors. */ - protected void initRomiMotor() { + protected final void initRomiMotor() { m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X); m_pwm.setSpeed(0.0); m_pwm.setZeroLatch(); 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 a913b554e6..f46feb1b2a 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 @@ -27,6 +27,7 @@ import java.util.function.BooleanSupplier; public abstract class Command implements Sendable { protected Set m_requirements = new HashSet<>(); + @SuppressWarnings("this-escape") protected Command() { String name = getClass().getName(); SendableRegistry.add(this, name.substring(name.lastIndexOf('.') + 1)); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java index 76a5276c75..099eba3b04 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java @@ -37,6 +37,7 @@ public class DeferredCommand extends Command { * omission of command requirements. Use {@link Set#of()} to easily construct a requirement * set. */ + @SuppressWarnings("this-escape") public DeferredCommand(Supplier supplier, Set requirements) { m_supplier = requireNonNullParam(supplier, "supplier", "DeferredCommand"); addRequirements(requirements.toArray(new Subsystem[0])); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java index dde5ae1f01..b685ef6b9d 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java @@ -32,6 +32,7 @@ public class FunctionalCommand extends Command { * @param isFinished the function that determines whether the command has finished * @param requirements the subsystems required by this command */ + @SuppressWarnings("this-escape") public FunctionalCommand( Runnable onInit, Runnable onExecute, 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 16d9c8a1ab..06663c9a80 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 @@ -86,6 +86,7 @@ public class MecanumControllerCommand extends Command { * voltages. * @param requirements The subsystems to require. */ + @SuppressWarnings("this-escape") public MecanumControllerCommand( Trajectory trajectory, Supplier pose, @@ -229,6 +230,7 @@ public class MecanumControllerCommand extends Command { * @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds. * @param requirements The subsystems to require. */ + @SuppressWarnings("this-escape") public MecanumControllerCommand( Trajectory trajectory, Supplier pose, diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java index ad1a12ad2d..b2d0938bd9 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java @@ -28,6 +28,7 @@ public class NotifierCommand extends Command { * @param period the period at which the notifier should run, in seconds * @param requirements the subsystems required by this command */ + @SuppressWarnings("this-escape") public NotifierCommand(Runnable toRun, double period, Subsystem... requirements) { m_notifier = new Notifier(toRun); m_period = period; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java index 84318de14a..e1c0dc893e 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java @@ -24,6 +24,7 @@ public abstract class PIDSubsystem extends SubsystemBase { * @param controller the PIDController to use * @param initialPosition the initial setpoint of the subsystem */ + @SuppressWarnings("this-escape") public PIDSubsystem(PIDController controller, double initialPosition) { m_controller = requireNonNullParam(controller, "controller", "PIDSubsystem"); setSetpoint(initialPosition); @@ -55,7 +56,7 @@ public abstract class PIDSubsystem extends SubsystemBase { * * @param setpoint the setpoint for the subsystem */ - public void setSetpoint(double setpoint) { + public final void setSetpoint(double setpoint) { m_controller.setSetpoint(setpoint); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java index 283b4bfd46..b8bb39843a 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java @@ -56,7 +56,7 @@ public abstract class ProfiledPIDSubsystem extends SubsystemBase { * * @param goal The goal state for the subsystem's motion profile. */ - public void setGoal(TrapezoidProfile.State goal) { + public final void setGoal(TrapezoidProfile.State goal) { m_controller.setGoal(goal); } @@ -65,7 +65,7 @@ public abstract class ProfiledPIDSubsystem extends SubsystemBase { * * @param goal The goal position for the subsystem's motion profile. */ - public void setGoal(double goal) { + public final void setGoal(double goal) { setGoal(new TrapezoidProfile.State(goal, 0)); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java index d6e93e88ba..f05b286f4d 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java @@ -35,6 +35,7 @@ public class ProxyCommand extends Command { * * @param command the command to run by proxy */ + @SuppressWarnings("this-escape") public ProxyCommand(Command command) { this(() -> command); setName("Proxy(" + command.getName() + ")"); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java index 9f19e4a792..48b37563dc 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java @@ -70,6 +70,7 @@ public class RamseteCommand extends Command { * the robot drive. * @param requirements The subsystems to require. */ + @SuppressWarnings("this-escape") public RamseteCommand( Trajectory trajectory, Supplier pose, @@ -109,6 +110,7 @@ public class RamseteCommand extends Command { * @param outputMetersPerSecond A function that consumes the computed left and right wheel speeds. * @param requirements The subsystems to require. */ + @SuppressWarnings("this-escape") public RamseteCommand( Trajectory trajectory, Supplier pose, diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java index 5b49ae0027..383cc9a647 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java @@ -29,6 +29,7 @@ public class RepeatCommand extends Command { * * @param command the command to run repeatedly */ + @SuppressWarnings("this-escape") public RepeatCommand(Command command) { m_command = requireNonNullParam(command, "command", "RepeatCommand"); CommandScheduler.getInstance().registerComposedCommands(command); 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 ea7a1ecaf7..4ab64b7cc5 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 @@ -16,6 +16,7 @@ import edu.wpi.first.util.sendable.SendableRegistry; */ public abstract class SubsystemBase implements Subsystem, Sendable { /** Constructor. */ + @SuppressWarnings("this-escape") public SubsystemBase() { String name = this.getClass().getSimpleName(); name = name.substring(name.lastIndexOf('.') + 1); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java index 3eacac3301..424a288b03 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java @@ -186,6 +186,7 @@ public class SwerveControllerCommand extends Command { * @param outputModuleStates The raw output module states from the position controllers. * @param requirements The subsystems to require. */ + @SuppressWarnings("this-escape") public SwerveControllerCommand( Trajectory trajectory, Supplier pose, diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java index 50416b6c30..3bfdbaebf5 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java @@ -35,6 +35,7 @@ public class TrapezoidProfileCommand extends Command { * @param currentState The current state * @param requirements The subsystems required by this command. */ + @SuppressWarnings("this-escape") public TrapezoidProfileCommand( TrapezoidProfile profile, Consumer output, @@ -60,6 +61,7 @@ public class TrapezoidProfileCommand extends Command { * This allows you to change goals at runtime. */ @Deprecated(since = "2024", forRemoval = true) + @SuppressWarnings("this-escape") public TrapezoidProfileCommand( TrapezoidProfile profile, Consumer output, Subsystem... requirements) { m_profile = requireNonNullParam(profile, "profile", "TrapezoidProfileCommand"); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java index 35c02e6ee6..54d4edef5c 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java @@ -74,7 +74,7 @@ public abstract class TrapezoidProfileSubsystem extends SubsystemBase { * * @param goal The goal state for the subsystem's motion profile. */ - public void setGoal(TrapezoidProfile.State goal) { + public final void setGoal(TrapezoidProfile.State goal) { m_goal = goal; } @@ -83,7 +83,7 @@ public abstract class TrapezoidProfileSubsystem extends SubsystemBase { * * @param goal The goal position for the subsystem's motion profile. */ - public void setGoal(double goal) { + public final void setGoal(double goal) { setGoal(new TrapezoidProfile.State(goal, 0)); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java index e7b32be8f6..828e8f5932 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java @@ -22,6 +22,7 @@ public class WaitCommand extends Command { * * @param seconds the time to wait, in seconds */ + @SuppressWarnings("this-escape") public WaitCommand(double seconds) { m_duration = seconds; SendableRegistry.setName(this, getName() + ": " + seconds + " seconds"); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java index c687f0a4fb..5e1cb05a07 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java @@ -23,6 +23,7 @@ public abstract class WrapperCommand extends Command { * @param command the command being wrapped. Trying to directly schedule this command or add it to * a composition will throw an exception. */ + @SuppressWarnings("this-escape") protected WrapperCommand(Command command) { CommandScheduler.getInstance().registerComposedCommands(command); m_command = command; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java index 301b518cec..0b11a44768 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16448_IMU.java @@ -257,6 +257,7 @@ public class ADIS16448_IMU implements AutoCloseable, Sendable { * @param port The SPI Port the gyro is plugged into * @param cal_time Calibration time */ + @SuppressWarnings("this-escape") public ADIS16448_IMU(final IMUAxis yaw_axis, SPI.Port port, CalibrationTime cal_time) { m_yaw_axis = yaw_axis; m_spi_port = port; @@ -527,7 +528,7 @@ public class ADIS16448_IMU implements AutoCloseable, Sendable { * @param new_cal_time New calibration time * @return 1 if the new calibration time is the same as the current one else 0 */ - public int configCalTime(CalibrationTime new_cal_time) { + public final int configCalTime(CalibrationTime new_cal_time) { if (m_calibration_time == new_cal_time) { return 1; } else { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java index 4016cd2020..652cc9325f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADIS16470_IMU.java @@ -287,6 +287,7 @@ public class ADIS16470_IMU implements AutoCloseable, Sendable { * @param port The SPI Port the gyro is plugged into * @param cal_time Calibration time */ + @SuppressWarnings("this-escape") public ADIS16470_IMU(IMUAxis yaw_axis, SPI.Port port, CalibrationTime cal_time) { m_yaw_axis = yaw_axis; m_calibration_time = cal_time.value; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java index 7ceff95a96..e96151bd76 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java @@ -95,6 +95,7 @@ public class ADXL345_I2C implements NTSendable, AutoCloseable { * @param range The range (+ or -) that the accelerometer will measure. * @param deviceAddress I2C address of the accelerometer (0x1D or 0x53) */ + @SuppressWarnings("this-escape") public ADXL345_I2C(I2C.Port port, Range range, int deviceAddress) { m_i2c = new I2C(port, deviceAddress); @@ -149,7 +150,7 @@ public class ADXL345_I2C implements NTSendable, AutoCloseable { * @param range The maximum acceleration, positive or negative, that the accelerometer will * measure. */ - public void setRange(Range range) { + public final void setRange(Range range) { final byte value; switch (range) { case k2G: diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java index 729144305a..b98b917f43 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java @@ -81,6 +81,7 @@ public class ADXL345_SPI implements NTSendable, AutoCloseable { * @param port The SPI port that the accelerometer is connected to * @param range The range (+ or -) that the accelerometer will measure. */ + @SuppressWarnings("this-escape") public ADXL345_SPI(SPI.Port port, Range range) { m_spi = new SPI(port); // simulation diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java index b094be374f..b4950682b1 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java @@ -93,6 +93,7 @@ public class ADXL362 implements NTSendable, AutoCloseable { * @param port The SPI port that the accelerometer is connected to * @param range The range (+ or -) that the accelerometer will measure. */ + @SuppressWarnings("this-escape") public ADXL362(SPI.Port port, Range range) { m_spi = new SPI(port); @@ -164,7 +165,7 @@ public class ADXL362 implements NTSendable, AutoCloseable { * @param range The maximum acceleration, positive or negative, that the accelerometer will * measure. */ - public void setRange(Range range) { + public final void setRange(Range range) { if (m_spi == null) { return; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java index cbe34c8337..799d43202b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java @@ -59,6 +59,7 @@ public class ADXRS450_Gyro implements Sendable, AutoCloseable { * * @param port The SPI port that the gyro is connected to */ + @SuppressWarnings("this-escape") public ADXRS450_Gyro(SPI.Port port) { m_spi = new SPI(port); @@ -113,7 +114,7 @@ public class ADXRS450_Gyro implements Sendable, AutoCloseable { * are in progress, this is typically done when the robot is first turned on while it's sitting at * rest before the competition starts. */ - public void calibrate() { + public final void calibrate() { if (m_spi == null) { return; } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java index 3ea9ef7947..0bdb2ffa2f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java @@ -36,6 +36,7 @@ public class AnalogAccelerometer implements Sendable, AutoCloseable { * * @param channel The channel number for the analog input the accelerometer is connected to */ + @SuppressWarnings("this-escape") public AnalogAccelerometer(final int channel) { this(new AnalogInput(channel), true); SendableRegistry.addChild(this, m_analogChannel); @@ -49,10 +50,12 @@ public class AnalogAccelerometer implements Sendable, AutoCloseable { * @param channel The existing AnalogInput object for the analog input the accelerometer is * connected to */ + @SuppressWarnings("this-escape") public AnalogAccelerometer(final AnalogInput channel) { this(channel, false); } + @SuppressWarnings("this-escape") private AnalogAccelerometer(final AnalogInput channel, final boolean allocatedChannel) { requireNonNullParam(channel, "channel", "AnalogAccelerometer"); m_allocatedChannel = allocatedChannel; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java index 8e458694e0..dc8b668bff 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogEncoder.java @@ -40,6 +40,7 @@ public class AnalogEncoder implements Sendable, AutoCloseable { * * @param analogInput the analog input to attach to */ + @SuppressWarnings("this-escape") public AnalogEncoder(AnalogInput analogInput) { m_analogInput = analogInput; init(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java index f5be4ad2d9..198283e34f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java @@ -31,7 +31,7 @@ public class AnalogGyro implements Sendable, AutoCloseable { private int m_gyroHandle; /** Initialize the gyro. Calibration is handled by calibrate(). */ - public void initGyro() { + private void initGyro() { if (m_gyroHandle == 0) { m_gyroHandle = AnalogGyroJNI.initializeAnalogGyro(m_analog.m_port); } @@ -78,6 +78,7 @@ public class AnalogGyro implements Sendable, AutoCloseable { * @param channel The analog channel the gyro is connected to. Gyros can only be used on on-board * channels 0-1. */ + @SuppressWarnings("this-escape") public AnalogGyro(int channel) { this(new AnalogInput(channel)); m_channelAllocated = true; @@ -91,6 +92,7 @@ public class AnalogGyro implements Sendable, AutoCloseable { * @param channel The AnalogInput object that the gyro is connected to. Gyros can only be used on * on-board channels 0-1. */ + @SuppressWarnings("this-escape") public AnalogGyro(AnalogInput channel) { requireNonNullParam(channel, "channel", "AnalogGyro"); @@ -108,6 +110,7 @@ public class AnalogGyro implements Sendable, AutoCloseable { * @param center Preset uncalibrated value to use as the accumulator center value. * @param offset Preset uncalibrated value to use as the gyro offset. */ + @SuppressWarnings("this-escape") public AnalogGyro(int channel, int center, double offset) { this(new AnalogInput(channel), center, offset); m_channelAllocated = true; @@ -123,6 +126,7 @@ public class AnalogGyro implements Sendable, AutoCloseable { * @param center Preset uncalibrated value to use as the accumulator center value. * @param offset Preset uncalibrated value to use as the gyro offset. */ + @SuppressWarnings("this-escape") public AnalogGyro(AnalogInput channel, int center, double offset) { requireNonNullParam(channel, "channel", "AnalogGyro"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java index e90bfd26d5..3c6458bfad 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -38,6 +38,7 @@ public class AnalogInput implements Sendable, AutoCloseable { * * @param channel The channel number to represent. 0-3 are on-board 4-7 are on the MXP port. */ + @SuppressWarnings("this-escape") public AnalogInput(final int channel) { AnalogJNI.checkAnalogInputChannel(channel); m_channel = channel; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java index 299d89c2ec..10f143c8fe 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java @@ -21,6 +21,7 @@ public class AnalogOutput implements Sendable, AutoCloseable { * * @param channel The channel number to represent. */ + @SuppressWarnings("this-escape") public AnalogOutput(final int channel) { SensorUtil.checkAnalogOutputChannel(channel); m_channel = channel; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java index 7d5858574d..1547349552 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java @@ -33,6 +33,7 @@ public class AnalogPotentiometer implements Sendable, AutoCloseable { * @param fullRange The scaling to multiply the fraction by to get a meaningful unit. * @param offset The offset to add to the scaled value for controlling the zero value */ + @SuppressWarnings("this-escape") public AnalogPotentiometer(final int channel, double fullRange, double offset) { this(new AnalogInput(channel), fullRange, offset); m_initAnalogInput = true; @@ -53,6 +54,7 @@ public class AnalogPotentiometer implements Sendable, AutoCloseable { * input. * @param offset The angular value (in desired units) representing the angular output at 0V. */ + @SuppressWarnings("this-escape") public AnalogPotentiometer(final AnalogInput input, double fullRange, double offset) { SendableRegistry.addLW(this, "AnalogPotentiometer", input.getChannel()); m_analogInput = input; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java index 8baa508120..77f8381608 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java @@ -39,6 +39,7 @@ public class AnalogTrigger implements Sendable, AutoCloseable { * * @param channel the port to use for the analog trigger */ + @SuppressWarnings("this-escape") public AnalogTrigger(final int channel) { this(new AnalogInput(channel)); m_ownsAnalog = true; @@ -51,6 +52,7 @@ public class AnalogTrigger implements Sendable, AutoCloseable { * * @param channel the AnalogInput to use for the analog trigger */ + @SuppressWarnings("this-escape") public AnalogTrigger(AnalogInput channel) { m_analogInput = channel; @@ -67,6 +69,7 @@ public class AnalogTrigger implements Sendable, AutoCloseable { * * @param input the DutyCycle to use for the analog trigger */ + @SuppressWarnings("this-escape") public AnalogTrigger(DutyCycle input) { m_dutyCycle = input; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java index 1a6b103a91..0b2654b478 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java @@ -28,6 +28,7 @@ public class BuiltInAccelerometer implements Sendable, AutoCloseable { * * @param range The range the accelerometer will measure */ + @SuppressWarnings("this-escape") public BuiltInAccelerometer(Range range) { setRange(range); HAL.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer"); @@ -50,7 +51,7 @@ public class BuiltInAccelerometer implements Sendable, AutoCloseable { * @param range The maximum acceleration, positive or negative, that the accelerometer will * measure. */ - public void setRange(Range range) { + public final void setRange(Range range) { AccelerometerJNI.setAccelerometerActive(false); switch (range) { 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 f2cfeb3908..e7a14bd659 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -31,6 +31,7 @@ public class Compressor implements Sendable, AutoCloseable { * @param module The module ID to use. * @param moduleType The module type to use. */ + @SuppressWarnings("this-escape") public Compressor(int module, PneumaticsModuleType moduleType) { m_module = PneumaticsBase.getForType(module, moduleType); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java index d8c5015f4e..26f921b3f4 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java @@ -58,6 +58,7 @@ public class Counter implements CounterBase, Sendable, AutoCloseable { * * @param mode The counter mode. */ + @SuppressWarnings("this-escape") public Counter(final Mode mode) { ByteBuffer index = ByteBuffer.allocateDirect(4); // set the byte order @@ -95,6 +96,7 @@ public class Counter implements CounterBase, Sendable, AutoCloseable { * * @param source the digital source to count */ + @SuppressWarnings("this-escape") public Counter(DigitalSource source) { this(); @@ -109,6 +111,7 @@ public class Counter implements CounterBase, Sendable, AutoCloseable { * * @param channel the DIO channel to use as the up source. 0-9 are on-board, 10-25 are on the MXP */ + @SuppressWarnings("this-escape") public Counter(int channel) { this(); setUpSource(channel); @@ -125,6 +128,7 @@ public class Counter implements CounterBase, Sendable, AutoCloseable { * @param downSource second source for direction * @param inverted true to invert the count */ + @SuppressWarnings("this-escape") public Counter( EncodingType encodingType, DigitalSource upSource, @@ -162,6 +166,7 @@ public class Counter implements CounterBase, Sendable, AutoCloseable { * * @param trigger the analog trigger to count */ + @SuppressWarnings("this-escape") public Counter(AnalogTrigger trigger) { this(); @@ -200,7 +205,7 @@ public class Counter implements CounterBase, Sendable, AutoCloseable { * * @param channel the DIO channel to count 0-9 are on-board, 10-25 are on the MXP */ - public void setUpSource(int channel) { + public final void setUpSource(int channel) { setUpSource(new DigitalInput(channel)); m_allocatedUpSource = true; SendableRegistry.addChild(this, m_upSource); @@ -401,7 +406,7 @@ public class Counter implements CounterBase, Sendable, AutoCloseable { * @param maxPeriod The maximum period where the counted device is considered moving in seconds. */ @Override - public void setMaxPeriod(double maxPeriod) { + public final void setMaxPeriod(double maxPeriod) { CounterJNI.setCounterMaxPeriod(m_counter, maxPeriod); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java index 8837d4167a..a656d9c700 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DSControlWord.java @@ -20,7 +20,7 @@ public class DSControlWord { } /** Update internal Driver Station control word. */ - public void refresh() { + public final void refresh() { DriverStation.refreshControlWordFromCache(m_controlWord); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java index 3422d34a97..2fcc9dd7a9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java @@ -20,6 +20,7 @@ import java.util.concurrent.locks.ReentrantLock; */ public class DigitalGlitchFilter implements Sendable, AutoCloseable { /** Configures the Digital Glitch Filter to its default settings. */ + @SuppressWarnings("this-escape") public DigitalGlitchFilter() { m_mutex.lock(); try { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java index 5b4cf5e829..ab3d5e5e4c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java @@ -27,6 +27,7 @@ public class DigitalInput extends DigitalSource implements Sendable { * * @param channel the DIO channel for the digital input 0-9 are on-board, 10-25 are on the MXP */ + @SuppressWarnings("this-escape") public DigitalInput(int channel) { SensorUtil.checkDigitalChannel(channel); m_channel = channel; diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java index 78e8bedbe2..a7446f6068 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java @@ -29,6 +29,7 @@ public class DigitalOutput extends DigitalSource implements Sendable { * @param channel the DIO channel to use for the digital output. 0-9 are on-board, 10-25 are on * the MXP */ + @SuppressWarnings("this-escape") public DigitalOutput(int channel) { SensorUtil.checkDigitalChannel(channel); m_channel = channel; 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 d749ccc579..6e037dfcf6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -53,7 +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") + @SuppressWarnings({"PMD.UseTryWithResources", "this-escape"}) public DoubleSolenoid( final int module, final PneumaticsModuleType moduleType, diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java index d500ba7b45..2e1795c0c4 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java @@ -33,6 +33,7 @@ public class DutyCycle implements Sendable, AutoCloseable { * * @param digitalSource The DigitalSource to use. */ + @SuppressWarnings("this-escape") public DutyCycle(DigitalSource digitalSource) { m_handle = DutyCycleJNI.initialize( diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java index afdcb3f3be..9c54dc1c9b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java @@ -41,6 +41,7 @@ public class DutyCycleEncoder implements Sendable, AutoCloseable { * * @param channel the channel to attach to */ + @SuppressWarnings("this-escape") public DutyCycleEncoder(int channel) { m_digitalInput = new DigitalInput(channel); m_ownsDutyCycle = true; @@ -53,6 +54,7 @@ public class DutyCycleEncoder implements Sendable, AutoCloseable { * * @param dutyCycle the duty cycle to attach to */ + @SuppressWarnings("this-escape") public DutyCycleEncoder(DutyCycle dutyCycle) { m_dutyCycle = dutyCycle; init(); @@ -63,6 +65,7 @@ public class DutyCycleEncoder implements Sendable, AutoCloseable { * * @param source the digital source to attach to */ + @SuppressWarnings("this-escape") public DutyCycleEncoder(DigitalSource source) { m_ownsDutyCycle = true; m_dutyCycle = new DutyCycle(source); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java index 2cbb5c769c..b70a5cdfb8 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -122,6 +122,7 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { * selected, then a counter object will be used and the returned value will either exactly * match the spec'd count or be double (2x) the spec'd count. */ + @SuppressWarnings("this-escape") public Encoder( final int channelA, final int channelB, @@ -152,6 +153,7 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { * @param reverseDirection represents the orientation of the encoder and inverts the output values * if necessary so forward represents positive values. */ + @SuppressWarnings("this-escape") public Encoder( final int channelA, final int channelB, final int indexChannel, boolean reverseDirection) { this(channelA, channelB, reverseDirection); @@ -222,6 +224,7 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { * selected then a counter object will be used and the returned value will either exactly * match the spec'd count or be double (2x) the spec'd count. */ + @SuppressWarnings("this-escape") public Encoder( DigitalSource sourceA, DigitalSource sourceB, @@ -492,7 +495,7 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { * * @param channel A DIO channel to set as the encoder index */ - public void setIndexSource(int channel) { + public final void setIndexSource(int channel) { setIndexSource(channel, IndexingType.kResetOnRisingEdge); } @@ -502,7 +505,7 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { * * @param source A digital source to set as the encoder index */ - public void setIndexSource(DigitalSource source) { + public final void setIndexSource(DigitalSource source) { setIndexSource(source, IndexingType.kResetOnRisingEdge); } @@ -513,7 +516,7 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { * @param channel A DIO channel to set as the encoder index * @param type The state that will cause the encoder to reset */ - public void setIndexSource(int channel, IndexingType type) { + public final void setIndexSource(int channel, IndexingType type) { if (m_allocatedI) { throw new AllocationException("Digital Input for Indexing already allocated"); } @@ -530,7 +533,7 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable { * @param source A digital source to set as the encoder index * @param type The state that will cause the encoder to reset */ - public void setIndexSource(DigitalSource source, IndexingType type) { + public final void setIndexSource(DigitalSource source, IndexingType type) { EncoderJNI.setEncoderIndexSource( m_encoder, source.getPortHandleForRouting(), diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java index 6f4062769d..3b1da84f2e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java @@ -62,6 +62,7 @@ public abstract class MotorSafety { } /** MotorSafety constructor. */ + @SuppressWarnings("this-escape") public MotorSafety() { synchronized (m_listMutex) { m_instanceList.add(this); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java index b0b3810c9d..76351560d7 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java @@ -54,6 +54,7 @@ public class PWM implements Sendable, AutoCloseable { * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port * @param registerSendable If true, adds this instance to SendableRegistry and LiveWindow */ + @SuppressWarnings("this-escape") public PWM(final int channel, final boolean registerSendable) { SensorUtil.checkPWMChannel(channel); m_channel = channel; @@ -200,7 +201,7 @@ public class PWM implements Sendable, AutoCloseable { } /** Temporarily disables the PWM output. The next set call will re-enable the output. */ - public void setDisabled() { + public final void setDisabled() { PWMJNI.setPWMDisabled(m_handle); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java index 13954264e4..3a4c2ab7f2 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistribution.java @@ -41,6 +41,7 @@ public class PowerDistribution implements Sendable, AutoCloseable { * @param module The CAN ID of the PDP/PDH. * @param moduleType Module type (CTRE or REV). */ + @SuppressWarnings("this-escape") public PowerDistribution(int module, ModuleType moduleType) { m_handle = PowerDistributionJNI.initialize(module, moduleType.value); m_module = PowerDistributionJNI.getModuleNumber(m_handle); @@ -54,6 +55,7 @@ public class PowerDistribution implements Sendable, AutoCloseable { * *

Detects the connected PDP/PDH using the default CAN ID (0 for CTRE and 1 for REV). */ + @SuppressWarnings("this-escape") public PowerDistribution() { m_handle = PowerDistributionJNI.initialize(kDefaultModule, PowerDistributionJNI.AUTOMATIC_TYPE); m_module = PowerDistributionJNI.getModuleNumber(m_handle); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java index a2a58d3e53..e68bf72108 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java @@ -110,6 +110,7 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { * @param channel The channel number for this relay (0 - 3). * @param direction The direction that the Relay object will control. */ + @SuppressWarnings("this-escape") public Relay(final int channel, Direction direction) { m_channel = channel; m_direction = requireNonNullParam(direction, "direction", "Relay"); @@ -279,6 +280,7 @@ public class Relay extends MotorSafety implements Sendable, AutoCloseable { * * @param direction The direction for the relay to operate in */ + @SuppressWarnings("this-escape") public void setDirection(Direction direction) { requireNonNullParam(direction, "direction", "setDirection"); if (m_direction == direction) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java index ada1839e5d..c2b35cad3a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java @@ -186,7 +186,7 @@ public class SerialPort implements AutoCloseable { } /** Disable termination behavior. */ - public void disableTermination() { + public final void disableTermination() { SerialPortJNI.serialDisableTermination(m_portHandle); } @@ -268,7 +268,7 @@ public class SerialPort implements AutoCloseable { * * @param timeout The number of seconds to wait for I/O. */ - public void setTimeout(double timeout) { + public final void setTimeout(double timeout) { SerialPortJNI.serialSetTimeout(m_portHandle, timeout); } @@ -283,7 +283,7 @@ public class SerialPort implements AutoCloseable { * * @param size The read buffer size. */ - public void setReadBufferSize(int size) { + public final void setReadBufferSize(int size) { SerialPortJNI.serialSetReadBufferSize(m_portHandle, size); } @@ -309,7 +309,7 @@ public class SerialPort implements AutoCloseable { * * @param mode The write buffer mode. */ - public void setWriteBufferMode(WriteBufferMode mode) { + public final void setWriteBufferMode(WriteBufferMode mode) { SerialPortJNI.serialSetWriteMode(m_portHandle, (byte) mode.value); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java index 1f1c747565..a4553fbc7a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java @@ -31,6 +31,7 @@ public class Servo extends PWM { * @param channel The PWM channel to which the servo is attached. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public Servo(final int channel) { super(channel); setBoundsMicroseconds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM); 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 be87444ae5..9c516da72f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -39,6 +39,7 @@ public class Solenoid implements Sendable, AutoCloseable { * @param moduleType The module type to use. * @param channel The channel the solenoid is on. */ + @SuppressWarnings("this-escape") public Solenoid(final int module, final PneumaticsModuleType moduleType, final int channel) { m_module = PneumaticsBase.getForType(module, moduleType); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java index 5a53b145f0..9bce0bc6c4 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java @@ -159,7 +159,7 @@ public class TimedRobot extends IterativeRobotBase { * @param callback The callback to run. * @param periodSeconds The period at which to run the callback in seconds. */ - public void addPeriodic(Runnable callback, double periodSeconds) { + public final void addPeriodic(Runnable callback, double periodSeconds) { m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, 0.0)); } @@ -174,7 +174,7 @@ public class TimedRobot extends IterativeRobotBase { * @param offsetSeconds The offset from the common starting time in seconds. This is useful for * scheduling a callback in a different timeslot relative to TimedRobot. */ - public void addPeriodic(Runnable callback, double periodSeconds, double offsetSeconds) { + public final void addPeriodic(Runnable callback, double periodSeconds, double offsetSeconds) { m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, offsetSeconds)); } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java index 4f948f5ae1..63e5ed4c99 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java @@ -83,7 +83,7 @@ public class Timer { * *

Make the timer startTime the current time so new requests will be relative now. */ - public void reset() { + public final void reset() { m_accumulatedTime = 0; m_startTime = getMsClock(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java index a2252c610b..15ca7fff81 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java @@ -36,7 +36,7 @@ public class Tracer { } /** Restarts the epoch timer. */ - public void resetTimer() { + public final void resetTimer() { m_startTime = RobotController.getFPGATime(); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java index fd2b05bf45..c5aab1f787 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java @@ -121,6 +121,7 @@ public class Ultrasonic implements Sendable, AutoCloseable { * @param echoChannel The digital input channel that receives the echo. The length of time that * the echo is high represents the round trip time of the ping, and the distance. */ + @SuppressWarnings("this-escape") public Ultrasonic(final int pingChannel, final int echoChannel) { m_pingChannel = new DigitalOutput(pingChannel); m_echoChannel = new DigitalInput(echoChannel); @@ -138,6 +139,7 @@ public class Ultrasonic implements Sendable, AutoCloseable { * 10uS pulse to start. * @param echoChannel The digital input object that times the return pulse to determine the range. */ + @SuppressWarnings("this-escape") public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) { requireNonNullParam(pingChannel, "pingChannel", "Ultrasonic"); requireNonNullParam(echoChannel, "echoChannel", "Ultrasonic"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java index 6828b9a53a..97fbf5b464 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/ExternalDirectionCounter.java @@ -34,6 +34,7 @@ public class ExternalDirectionCounter implements Sendable, AutoCloseable { * @param countSource The source for counting. * @param directionSource The source for selecting count direction. */ + @SuppressWarnings("this-escape") public ExternalDirectionCounter(DigitalSource countSource, DigitalSource directionSource) { m_countSource = requireNonNullParam(countSource, "countSource", "ExternalDirectionCounter"); m_directionSource = diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java index 5bd8e7ea78..6bef24deaa 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/Tachometer.java @@ -34,6 +34,7 @@ public class Tachometer implements Sendable, AutoCloseable { * * @param source The DigitalSource (e.g. DigitalInput) of the Tachometer. */ + @SuppressWarnings("this-escape") public Tachometer(DigitalSource source) { m_source = requireNonNullParam(source, "source", "Tachometer"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java index c89c11811c..ed9f35e971 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/counter/UpDownCounter.java @@ -32,6 +32,7 @@ public class UpDownCounter implements Sendable, AutoCloseable { * @param upSource The up count source (can be null). * @param downSource The down count source (can be null). */ + @SuppressWarnings("this-escape") public UpDownCounter(DigitalSource upSource, DigitalSource downSource) { ByteBuffer index = ByteBuffer.allocateDirect(4); // set the byte order @@ -92,7 +93,7 @@ public class UpDownCounter implements Sendable, AutoCloseable { } /** Resets the current count. */ - public void reset() { + public final void reset() { CounterJNI.resetCounter(m_handle); } 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 9a1f2ba46c..a6a59c17e5 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 @@ -128,6 +128,7 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC * @param leftMotor Left motor. * @param rightMotor Right motor. */ + @SuppressWarnings("this-escape") public DifferentialDrive(MotorController leftMotor, MotorController rightMotor) { requireNonNullParam(leftMotor, "leftMotor", "DifferentialDrive"); requireNonNullParam(rightMotor, "rightMotor", "DifferentialDrive"); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index 181e2753b0..abdfefedd6 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -104,6 +104,7 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea * @param frontRightMotor The motor on the front-right corner. * @param rearRightMotor The motor on the rear-right corner. */ + @SuppressWarnings("this-escape") public MecanumDrive( MotorController frontLeftMotor, MotorController rearLeftMotor, diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java index c4e931d2f8..933773b4b8 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java @@ -36,6 +36,7 @@ public abstract class RobotDriveBase extends MotorSafety { } /** RobotDriveBase constructor. */ + @SuppressWarnings("this-escape") public RobotDriveBase() { setSafetyEnabled(true); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java index 5f0f26b596..9d669078bd 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/DMC60.java @@ -32,6 +32,7 @@ public class DMC60 extends PWMMotorController { * @param channel The PWM channel that the DMC60 is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public DMC60(final int channel) { super("DMC60", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java index f07206784e..4a0ac85572 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Jaguar.java @@ -31,6 +31,7 @@ public class Jaguar extends PWMMotorController { * @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public Jaguar(final int channel) { super("Jaguar", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java index d9da3c8f1f..88e7efe132 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/MotorControllerGroup.java @@ -21,6 +21,7 @@ public class MotorControllerGroup implements MotorController, Sendable, AutoClos * @param motorController The first MotorController to add * @param motorControllers The MotorControllers to add */ + @SuppressWarnings("this-escape") public MotorControllerGroup( MotorController motorController, MotorController... motorControllers) { m_motorControllers = new MotorController[motorControllers.length + 1]; @@ -29,6 +30,7 @@ public class MotorControllerGroup implements MotorController, Sendable, AutoClos init(); } + @SuppressWarnings("this-escape") public MotorControllerGroup(MotorController[] motorControllers) { m_motorControllers = Arrays.copyOf(motorControllers, motorControllers.length); init(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java index 25c29acfdc..c5aac4f090 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/NidecBrushless.java @@ -30,6 +30,7 @@ public class NidecBrushless extends MotorSafety * @param dioChannel The DIO channel that the Nidec Brushless controller is attached to. 0-9 are * on-board, 10-25 are on the MXP port */ + @SuppressWarnings("this-escape") public NidecBrushless(final int pwmChannel, final int dioChannel) { setSafetyEnabled(false); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java index 68817a1dad..0d2f83717b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java @@ -23,6 +23,7 @@ public abstract class PWMMotorController extends MotorSafety * @param channel The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are * on the MXP port */ + @SuppressWarnings("this-escape") protected PWMMotorController(final String name, final int channel) { m_pwm = new PWM(channel, false); SendableRegistry.addLW(this, name, channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java index ede5f5de0b..205d70a0de 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMSparkMax.java @@ -31,6 +31,7 @@ public class PWMSparkMax extends PWMMotorController { * * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port */ + @SuppressWarnings("this-escape") public PWMSparkMax(final int channel) { super("PWMSparkMax", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java index 29ac7663be..2211fa5269 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonFX.java @@ -32,6 +32,7 @@ public class PWMTalonFX extends PWMMotorController { * @param channel The PWM channel that the Talon FX is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public PWMTalonFX(final int channel) { super("PWMTalonFX", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java index 085cd869bf..4677627f23 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMTalonSRX.java @@ -32,6 +32,7 @@ public class PWMTalonSRX extends PWMMotorController { * @param channel The PWM channel that the Talon SRX is attached to. 0-9 are on-board, 10-19 are * on the MXP port */ + @SuppressWarnings("this-escape") public PWMTalonSRX(final int channel) { super("PWMTalonSRX", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java index a38e93691c..f9960b0278 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVenom.java @@ -31,6 +31,7 @@ public class PWMVenom extends PWMMotorController { * @param channel The PWM channel that the Venom is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public PWMVenom(final int channel) { super("PWMVenom", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java index 555614a9a6..daa70f3478 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMVictorSPX.java @@ -32,6 +32,7 @@ public class PWMVictorSPX extends PWMMotorController { * @param channel The PWM channel that the PWMVictorSPX is attached to. 0-9 are on-board, 10-19 * are on the MXP port */ + @SuppressWarnings("this-escape") public PWMVictorSPX(final int channel) { super("PWMVictorSPX", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java index 7cdb03573c..31246bc5c1 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/SD540.java @@ -32,6 +32,7 @@ public class SD540 extends PWMMotorController { * @param channel The PWM channel that the SD540 is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public SD540(final int channel) { super("SD540", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java index cc926215ba..d57b626a10 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Spark.java @@ -32,6 +32,7 @@ public class Spark extends PWMMotorController { * @param channel The PWM channel that the SPARK is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public Spark(final int channel) { super("Spark", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java index dd9e473a92..bcbad60738 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Talon.java @@ -31,6 +31,7 @@ public class Talon extends PWMMotorController { * @param channel The PWM channel that the Talon is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public Talon(final int channel) { super("Talon", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java index d9bd15264f..1a816add18 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/Victor.java @@ -35,6 +35,7 @@ public class Victor extends PWMMotorController { * @param channel The PWM channel that the Victor is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public Victor(final int channel) { super("Victor", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java index aa262d042e..09ba3c6290 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/VictorSP.java @@ -32,6 +32,7 @@ public class VictorSP extends PWMMotorController { * @param channel The PWM channel that the VictorSP is attached to. 0-9 are on-board, 10-19 are on * the MXP port */ + @SuppressWarnings("this-escape") public VictorSP(final int channel) { super("VictorSP", channel); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java index 322d897479..6ec8002730 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ElevatorSim.java @@ -41,6 +41,7 @@ public class ElevatorSim extends LinearSystemSim { * @param startingHeightMeters The starting height of the elevator. * @param measurementStdDevs The standard deviations of the measurements. */ + @SuppressWarnings("this-escape") public ElevatorSim( LinearSystem plant, DCMotor gearbox, @@ -221,7 +222,7 @@ public class ElevatorSim extends LinearSystemSim { * @param positionMeters The new position in meters. * @param velocityMetersPerSecond New velocity in meters per second. */ - public void setState(double positionMeters, double velocityMetersPerSecond) { + public final void setState(double positionMeters, double velocityMetersPerSecond) { setState( VecBuilder.fill( MathUtil.clamp(positionMeters, m_minHeight, m_maxHeight), velocityMetersPerSecond)); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java index f55b038499..b6f21e313c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/JoystickSim.java @@ -15,6 +15,7 @@ public class JoystickSim extends GenericHIDSim { * * @param joystick joystick to simulate */ + @SuppressWarnings("this-escape") public JoystickSim(Joystick joystick) { super(joystick); m_joystick = joystick; @@ -29,6 +30,7 @@ public class JoystickSim extends GenericHIDSim { * * @param port port number */ + @SuppressWarnings("this-escape") public JoystickSim(int port) { super(port); // default to a reasonable joystick configuration diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java index fa19760974..822b1db58f 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS4ControllerSim.java @@ -13,6 +13,7 @@ public class PS4ControllerSim extends GenericHIDSim { * * @param joystick controller to simulate */ + @SuppressWarnings("this-escape") public PS4ControllerSim(PS4Controller joystick) { super(joystick); setAxisCount(6); @@ -25,6 +26,7 @@ public class PS4ControllerSim extends GenericHIDSim { * * @param port port number */ + @SuppressWarnings("this-escape") public PS4ControllerSim(int port) { super(port); setAxisCount(6); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java index d886bd6e71..e11cdd084c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/PS5ControllerSim.java @@ -13,6 +13,7 @@ public class PS5ControllerSim extends GenericHIDSim { * * @param joystick controller to simulate */ + @SuppressWarnings("this-escape") public PS5ControllerSim(PS5Controller joystick) { super(joystick); setAxisCount(6); @@ -25,6 +26,7 @@ public class PS5ControllerSim extends GenericHIDSim { * * @param port port number */ + @SuppressWarnings("this-escape") public PS5ControllerSim(int port) { super(port); setAxisCount(6); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java index af2ee85b87..46e04411e1 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SingleJointedArmSim.java @@ -49,6 +49,7 @@ public class SingleJointedArmSim extends LinearSystemSim { * @param startingAngleRads The initial position of the Arm simulation in radians. * @param measurementStdDevs The standard deviations of the measurements. */ + @SuppressWarnings("this-escape") public SingleJointedArmSim( LinearSystem plant, DCMotor gearbox, @@ -180,7 +181,7 @@ public class SingleJointedArmSim extends LinearSystemSim { * @param angleRadians The new angle in radians. * @param velocityRadPerSec The new angular velocity in radians per second. */ - public void setState(double angleRadians, double velocityRadPerSec) { + public final void setState(double angleRadians, double velocityRadPerSec) { setState( VecBuilder.fill(MathUtil.clamp(angleRadians, m_minAngle, m_maxAngle), velocityRadPerSec)); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java index 41d200e161..37e0bda32d 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/XboxControllerSim.java @@ -13,6 +13,7 @@ public class XboxControllerSim extends GenericHIDSim { * * @param joystick controller to simulate */ + @SuppressWarnings("this-escape") public XboxControllerSim(XboxController joystick) { super(joystick); setAxisCount(6); @@ -25,6 +26,7 @@ public class XboxControllerSim extends GenericHIDSim { * * @param port port number */ + @SuppressWarnings("this-escape") public XboxControllerSim(int port) { super(port); setAxisCount(6); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java index bfacb428cd..4b02c4fe02 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/Field2d.java @@ -31,6 +31,7 @@ import java.util.List; */ public class Field2d implements NTSendable, AutoCloseable { /** Constructor. */ + @SuppressWarnings("this-escape") public Field2d() { FieldObject2d obj = new FieldObject2d("Robot"); obj.setPose(new Pose2d()); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java index 28484a39e4..ea7fda38bf 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java @@ -82,7 +82,7 @@ public class MechanismLigament2d extends MechanismObject2d { * * @param degrees the angle in degrees */ - public synchronized void setAngle(double degrees) { + public final synchronized void setAngle(double degrees) { m_angle = degrees; if (m_angleEntry != null) { m_angleEntry.set(degrees); @@ -115,7 +115,7 @@ public class MechanismLigament2d extends MechanismObject2d { * * @param length the line length */ - public synchronized void setLength(double length) { + public final synchronized void setLength(double length) { m_length = length; if (m_lengthEntry != null) { m_lengthEntry.set(length); @@ -139,7 +139,7 @@ public class MechanismLigament2d extends MechanismObject2d { * * @param color the color of the line */ - public synchronized void setColor(Color8Bit color) { + public final synchronized void setColor(Color8Bit color) { m_color = String.format("#%02X%02X%02X", color.red, color.green, color.blue); if (m_colorEntry != null) { m_colorEntry.set(m_color); @@ -177,7 +177,7 @@ public class MechanismLigament2d extends MechanismObject2d { * * @param weight the line thickness */ - public synchronized void setLineWeight(double weight) { + public final synchronized void setLineWeight(double weight) { m_weight = weight; if (m_weightEntry != null) { m_weightEntry.set(weight); 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 7f3b93c1f4..e905ebc635 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 @@ -53,6 +53,7 @@ public class SendableChooser implements Sendable, AutoCloseable { private static final AtomicInteger s_instances = new AtomicInteger(); /** Instantiates a {@link SendableChooser}. */ + @SuppressWarnings("this-escape") public SendableChooser() { m_instance = s_instances.getAndIncrement(); SendableRegistry.add(this, "SendableChooser", m_instance); diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java index 04397c2c4c..a630c3e1af 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java @@ -10,6 +10,7 @@ import edu.wpi.first.util.sendable.SendableRegistry; /** A mock sendable that marks itself as an actuator. */ public class MockActuatorSendable implements Sendable { + @SuppressWarnings("this-escape") public MockActuatorSendable(String name) { SendableRegistry.add(this, name); } diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java index 7e8c7786bb..cf852c30d0 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java @@ -37,6 +37,7 @@ public class BangBangController implements Sendable { * * @param tolerance Tolerance for {@link #atSetpoint() atSetpoint}. */ + @SuppressWarnings("this-escape") public BangBangController(double tolerance) { instances++; @@ -89,7 +90,7 @@ public class BangBangController implements Sendable { * * @param tolerance Position error which is tolerable. */ - public void setTolerance(double tolerance) { + public final void setTolerance(double tolerance) { m_tolerance = tolerance; } diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java index c406203b20..50ff576f95 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ControlAffinePlantInversionFeedforward.java @@ -144,13 +144,13 @@ public class ControlAffinePlantInversionFeedforward initialState) { + public final void reset(Matrix initialState) { m_r = initialState; m_uff.fill(0.0); } /** Resets the feedforward with a zero initial state vector. */ - public void reset() { + public final void reset() { m_r.fill(0.0); m_uff.fill(0.0); } diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ImplicitModelFollower.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ImplicitModelFollower.java index 6fdf1f319f..de370e9af1 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/ImplicitModelFollower.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ImplicitModelFollower.java @@ -99,7 +99,7 @@ public class ImplicitModelFollower initialState) { + public final void reset(Matrix initialState) { m_r = initialState; m_uff.fill(0.0); } /** Resets the feedforward with a zero initial state vector. */ - public void reset() { + public final void reset() { m_r.fill(0.0); m_uff.fill(0.0); } 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 e3aa90aa4b..800ea4007a 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 @@ -221,7 +221,7 @@ public class LinearQuadraticRegulator(m_states, Nat.N1()); m_P = m_initP; } diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java index d74db4e4d9..8ca1db0a86 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilter.java @@ -172,7 +172,7 @@ public class KalmanFilter(m_states, Nat.N1()); m_P = m_initP; } diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java index bb30f25b4d..1d9a54b931 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java @@ -80,7 +80,7 @@ public class PoseEstimator> { * numbers to trust global measurements from vision less. This matrix is in the form [x, y, * theta]ᵀ, with units in meters and radians. */ - public void setVisionMeasurementStdDevs(Matrix visionMeasurementStdDevs) { + public final void setVisionMeasurementStdDevs(Matrix visionMeasurementStdDevs) { var r = new double[3]; for (int i = 0; i < 3; ++i) { r[i] = visionMeasurementStdDevs.get(i, 0) * visionMeasurementStdDevs.get(i, 0); diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java index bf31ae7293..801c601143 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java @@ -115,7 +115,7 @@ public class SteadyStateKalmanFilter(m_states, Nat.N1()); } 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 2c1e1e6efa..c982d08450 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 @@ -323,7 +323,7 @@ public class UnscentedKalmanFilter(m_states, Nat.N1()); m_S = new Matrix<>(m_states, m_states); m_sigmasF = new Matrix<>(new SimpleMatrix(m_states.getNum(), 2 * m_states.getNum() + 1)); 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 255732415b..8bd6c15abf 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 @@ -265,7 +265,7 @@ public class LinearSystemLoop initialState) { + public final void reset(Matrix initialState) { m_nextR.fill(0.0); m_controller.reset(); m_feedforward.reset(initialState); diff --git a/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceAnnouncer.java b/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceAnnouncer.java index 9ccb322745..39989e156d 100644 --- a/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceAnnouncer.java +++ b/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceAnnouncer.java @@ -25,6 +25,7 @@ public class MulticastServiceAnnouncer implements AutoCloseable { * @param port port * @param txt txt */ + @SuppressWarnings("this-escape") public MulticastServiceAnnouncer( String serviceName, String serviceType, int port, Map txt) { String[] keys = txt.keySet().toArray(String[]::new); @@ -41,6 +42,7 @@ public class MulticastServiceAnnouncer implements AutoCloseable { * @param serviceType service type * @param port port */ + @SuppressWarnings("this-escape") public MulticastServiceAnnouncer(String serviceName, String serviceType, int port) { m_handle = WPINetJNI.createMulticastServiceAnnouncer(serviceName, serviceType, port, null, null); diff --git a/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceResolver.java b/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceResolver.java index b676f4c2dc..8d70fd7ee3 100644 --- a/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceResolver.java +++ b/wpinet/src/main/java/edu/wpi/first/net/MulticastServiceResolver.java @@ -21,6 +21,7 @@ public class MulticastServiceResolver implements AutoCloseable { * * @param serviceType service type to look for */ + @SuppressWarnings("this-escape") public MulticastServiceResolver(String serviceType) { m_handle = WPINetJNI.createMulticastServiceResolver(serviceType); m_cleanable = WPICleaner.register(this, cleanupAction(m_handle)); diff --git a/wpiutil/src/main/java/edu/wpi/first/util/struct/DynamicStruct.java b/wpiutil/src/main/java/edu/wpi/first/util/struct/DynamicStruct.java index 165f7db1cd..1f9fdc379a 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/struct/DynamicStruct.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/struct/DynamicStruct.java @@ -593,24 +593,24 @@ public final class DynamicStruct { case 1: { byte val = m_data.get(field.m_offset + arrIndex); - val &= ~(field.getBitMask() << field.m_bitShift); - val |= (value & field.getBitMask()) << field.m_bitShift; + val &= (byte) ~(field.getBitMask() << field.m_bitShift); + val |= (byte) ((value & field.getBitMask()) << field.m_bitShift); m_data.put(field.m_offset + arrIndex, val); break; } case 2: { short val = m_data.getShort(field.m_offset + arrIndex * 2); - val &= ~(field.getBitMask() << field.m_bitShift); - val |= (value & field.getBitMask()) << field.m_bitShift; + val &= (short) ~(field.getBitMask() << field.m_bitShift); + val |= (short) ((value & field.getBitMask()) << field.m_bitShift); m_data.putShort(field.m_offset + arrIndex * 2, val); break; } case 4: { int val = m_data.getInt(field.m_offset + arrIndex * 4); - val &= ~(field.getBitMask() << field.m_bitShift); - val |= (value & field.getBitMask()) << field.m_bitShift; + val &= (int) ~(field.getBitMask() << field.m_bitShift); + val |= (int) ((value & field.getBitMask()) << field.m_bitShift); m_data.putInt(field.m_offset + arrIndex * 4, val); break; }