diff --git a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
index 01a08d4c24..4ad1b87623 100644
--- a/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
+++ b/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
@@ -33,12 +33,10 @@ import java.util.concurrent.atomic.AtomicInteger;
* Singleton class for creating and keeping camera servers. Also publishes camera information to
* NetworkTables.
*/
-@SuppressWarnings("PMD.UnusedPrivateField")
public final class CameraServer {
public static final int kBasePort = 1181;
private static final String kPublishName = "/CameraPublisher";
- private static CameraServer server;
private static final AtomicInteger m_defaultUsbDevice = new AtomicInteger();
private static String m_primarySourceName;
@@ -63,6 +61,7 @@ public final class CameraServer {
// - "PropertyInfo/{Property}" - Property supporting information
// Listener for video events
+ @SuppressWarnings("PMD.UnusedPrivateField")
private static final VideoListener m_videoListener =
new VideoListener(
event -> {
@@ -185,6 +184,7 @@ public final class CameraServer {
0x4fff,
true);
+ @SuppressWarnings("PMD.UnusedPrivateField")
private static final int m_tableListener =
NetworkTableInstance.getDefault()
.addEntryListener(
@@ -243,10 +243,15 @@ public final class CameraServer {
}
},
EntryListenerFlags.kImmediate | EntryListenerFlags.kUpdate);
+
private static int m_nextPort = kBasePort;
private static String[] m_addresses = new String[0];
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Return URI of source with the given index.
+ *
+ * @param source Source index.
+ */
private static String makeSourceValue(int source) {
switch (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))) {
case kUsb:
@@ -267,12 +272,21 @@ public final class CameraServer {
}
}
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Return URI of stream with the given address and port.
+ *
+ * @param address Stream IP address.
+ * @param port Stream remote port.
+ */
private static String makeStreamValue(String address, int port) {
return "mjpg:http://" + address + ":" + port + "/?action=stream";
}
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Return URI of sink stream with the given index.
+ *
+ * @param sink Sink index.
+ */
private static synchronized String[] getSinkStreamValues(int sink) {
// Ignore all but MjpegServer
if (VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) != VideoSink.Kind.kMjpeg) {
@@ -302,7 +316,11 @@ public final class CameraServer {
return values.toArray(new String[0]);
}
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Return list of stream source URIs for the given source index.
+ *
+ * @param source Source index.
+ */
private static synchronized String[] getSourceStreamValues(int source) {
// Ignore all but HttpCamera
if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
@@ -337,7 +355,7 @@ public final class CameraServer {
return values;
}
- @SuppressWarnings("MissingJavadocMethod")
+ /** Update list of stream URIs. */
private static synchronized void updateStreamValues() {
// Over all the sinks...
for (VideoSink i : m_sinks.values()) {
@@ -383,7 +401,7 @@ public final class CameraServer {
}
}
- @SuppressWarnings("MissingJavadocMethod")
+ /** Provide string description of pixel format. */
private static String pixelFormatToString(PixelFormat pixelFormat) {
switch (pixelFormat) {
case kMJPEG:
@@ -401,9 +419,11 @@ public final class CameraServer {
}
}
- /// Provide string description of video mode.
- /// The returned string is "{width}x{height} {format} {fps} fps".
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Provide string description of video mode.
+ *
+ *
The returned string is "{width}x{height} {format} {fps} fps".
+ */
private static String videoModeToString(VideoMode mode) {
return mode.width
+ "x"
@@ -415,7 +435,11 @@ public final class CameraServer {
+ " fps";
}
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Get list of video modes for the given source handle.
+ *
+ * @param sourceHandle Source handle.
+ */
private static String[] getSourceModeValues(int sourceHandle) {
VideoMode[] modes = CameraServerJNI.enumerateSourceVideoModes(sourceHandle);
String[] modeStrings = new String[modes.length];
@@ -425,7 +449,13 @@ public final class CameraServer {
return modeStrings;
}
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Publish a source property value to NetworkTables.
+ *
+ * @param table NetworkTable to which to push value.
+ * @param event Video event.
+ * @param isNew Whether the property value hasn't been pushed to NetworkTables before.
+ */
private static void putSourcePropertyValue(NetworkTable table, VideoEvent event, boolean isNew) {
String name;
String infoName;
diff --git a/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java b/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java
index df856e8d2d..04b122921d 100644
--- a/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java
+++ b/cscore/src/main/java/edu/wpi/first/cscore/UsbCameraInfo.java
@@ -5,6 +5,7 @@
package edu.wpi.first.cscore;
/** USB camera information. */
+@SuppressWarnings("MemberName")
public class UsbCameraInfo {
/**
* Create a new set of UsbCameraInfo.
@@ -28,26 +29,20 @@ public class UsbCameraInfo {
}
/** Device number (e.g. N in '/dev/videoN' on Linux). */
- @SuppressWarnings("MemberName")
public int dev;
/** Path to device if available (e.g. '/dev/video0' on Linux). */
- @SuppressWarnings("MemberName")
public String path;
/** Vendor/model name of the camera as provided by the USB driver. */
- @SuppressWarnings("MemberName")
public String name;
/** Other path aliases to device (e.g. '/dev/v4l/by-id/...' etc on Linux). */
- @SuppressWarnings("MemberName")
public String[] otherPaths;
/** USB vendor id. */
- @SuppressWarnings("MemberName")
public int vendorId;
/** USB product id. */
- @SuppressWarnings("MemberName")
public int productId;
}
diff --git a/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java b/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java
index 50f041c37a..0c60d6df32 100644
--- a/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java
+++ b/cscore/src/main/java/edu/wpi/first/cscore/VideoEvent.java
@@ -5,6 +5,7 @@
package edu.wpi.first.cscore;
/** Video event. */
+@SuppressWarnings("MemberName")
public class VideoEvent {
public enum Kind {
kUnknown(0x0000),
@@ -117,39 +118,29 @@ public class VideoEvent {
this.listener = listener;
}
- @SuppressWarnings("MemberName")
public Kind kind;
// Valid for kSource* and kSink* respectively
- @SuppressWarnings("MemberName")
public int sourceHandle;
- @SuppressWarnings("MemberName")
public int sinkHandle;
// Source/sink/property name
- @SuppressWarnings("MemberName")
public String name;
// Fields for kSourceVideoModeChanged event
- @SuppressWarnings("MemberName")
public VideoMode mode;
// Fields for kSourceProperty* events
- @SuppressWarnings("MemberName")
public int propertyHandle;
- @SuppressWarnings("MemberName")
public VideoProperty.Kind propertyKind;
- @SuppressWarnings("MemberName")
public int value;
- @SuppressWarnings("MemberName")
public String valueStr;
// Listener that was triggered
- @SuppressWarnings("MemberName")
public int listener;
public VideoSource getSource() {
diff --git a/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java b/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java
index 0d77461432..652d12db76 100644
--- a/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java
+++ b/cscore/src/main/java/edu/wpi/first/cscore/VideoListener.java
@@ -64,7 +64,6 @@ public class VideoListener implements AutoCloseable {
private static boolean s_waitQueue;
private static final Condition s_waitQueueCond = s_lock.newCondition();
- @SuppressWarnings("PMD.AvoidCatchingThrowable")
private static void startThread() {
s_thread =
new Thread(
diff --git a/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java b/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java
index 726b2106aa..57bd5fd253 100644
--- a/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java
+++ b/cscore/src/main/java/edu/wpi/first/cscore/VideoMode.java
@@ -5,6 +5,7 @@
package edu.wpi.first.cscore;
/** Video mode. */
+@SuppressWarnings("MemberName")
public class VideoMode {
public enum PixelFormat {
kUnknown(0),
@@ -62,18 +63,14 @@ public class VideoMode {
}
/** Pixel format. */
- @SuppressWarnings("MemberName")
public PixelFormat pixelFormat;
/** Width in pixels. */
- @SuppressWarnings("MemberName")
public int width;
/** Height in pixels. */
- @SuppressWarnings("MemberName")
public int height;
/** Frames per second. */
- @SuppressWarnings("MemberName")
public int fps;
}
diff --git a/hal/src/generate/FRCNetComm.java.in b/hal/src/generate/FRCNetComm.java.in
index ce21889800..703e0349e5 100644
--- a/hal/src/generate/FRCNetComm.java.in
+++ b/hal/src/generate/FRCNetComm.java.in
@@ -7,7 +7,6 @@ package edu.wpi.first.hal;
/**
* JNI wrapper for library FRC_NetworkCommunication
.
*/
-@SuppressWarnings({"MethodName", "LineLength"})
public class FRCNetComm {
/**
* Resource type from UsageReporting.
diff --git a/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java b/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
index 9340748f08..441ce9f472 100644
--- a/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
+++ b/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
@@ -5,12 +5,11 @@
package edu.wpi.first.hal;
/** Structure for holding the values stored in an accumulator. */
+@SuppressWarnings("MemberName")
public class AccumulatorResult {
/** The total value accumulated. */
- @SuppressWarnings("MemberName")
public long value;
/** The number of sample value was accumulated over. */
- @SuppressWarnings("MemberName")
public long count;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java b/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
index c732ec6ca7..1dd80a7b46 100644
--- a/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class AddressableLEDJNI extends JNIWrapper {
public static native int initialize(int pwmHandle);
diff --git a/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java b/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
index e2deaddb35..b80388d722 100644
--- a/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
@@ -111,6 +111,5 @@ public class AnalogJNI extends JNIWrapper {
public static native boolean getAnalogTriggerOutput(int analogTriggerHandle, int type);
- @SuppressWarnings("AbbreviationAsWordInName")
public static native int getAnalogTriggerFPGAIndex(int analogTriggerHandle);
}
diff --git a/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java b/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
index 31cf973b3e..227da4d816 100644
--- a/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class CANAPIJNI extends JNIWrapper {
public static native int initializeCAN(int manufacturer, int deviceId, int deviceType);
diff --git a/hal/src/main/java/edu/wpi/first/hal/CANData.java b/hal/src/main/java/edu/wpi/first/hal/CANData.java
index 94e9f573c4..0a644f6494 100644
--- a/hal/src/main/java/edu/wpi/first/hal/CANData.java
+++ b/hal/src/main/java/edu/wpi/first/hal/CANData.java
@@ -4,14 +4,10 @@
package edu.wpi.first.hal;
+@SuppressWarnings("MemberName")
public class CANData {
- @SuppressWarnings("MemberName")
public final byte[] data = new byte[8];
-
- @SuppressWarnings("MemberName")
public int length;
-
- @SuppressWarnings("MemberName")
public long timestamp;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java b/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java
index 20d5cb8c40..e94b183a44 100644
--- a/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/CTREPCMJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class CTREPCMJNI extends JNIWrapper {
public static native int initialize(int module);
diff --git a/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java b/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
index 63c9c259f2..ed8e86fdf8 100644
--- a/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class DIOJNI extends JNIWrapper {
public static native int initializeDIOPort(int halPortHandle, boolean input);
diff --git a/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java b/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
index 21c06f1497..9a0cfeb5f9 100644
--- a/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/DMAJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class DMAJNI extends JNIWrapper {
public static native int initialize();
diff --git a/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java b/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
index 78a0e99a9a..22f21c8c6b 100644
--- a/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
+++ b/hal/src/main/java/edu/wpi/first/hal/DMAJNISample.java
@@ -7,7 +7,6 @@ package edu.wpi.first.hal;
import java.util.HashMap;
import java.util.Map;
-@SuppressWarnings("AbbreviationAsWordInName")
public class DMAJNISample {
private static final int kEnable_Accumulator0 = 8;
private static final int kEnable_Accumulator1 = 9;
diff --git a/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java b/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
index a1bba6f2de..2dcf0f2113 100644
--- a/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
@@ -17,6 +17,5 @@ public class DutyCycleJNI extends JNIWrapper {
public static native int getOutputScaleFactor(int handle);
- @SuppressWarnings("AbbreviationAsWordInName")
public static native int getFPGAIndex(int handle);
}
diff --git a/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java b/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
index f67e3a5f68..50ecc91d8b 100644
--- a/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
@@ -50,7 +50,6 @@ public class EncoderJNI extends JNIWrapper {
public static native void setEncoderIndexSource(
int encoderHandle, int digitalSourceHandle, int analogTriggerType, int indexingType);
- @SuppressWarnings("AbbreviationAsWordInName")
public static native int getEncoderFPGAIndex(int encoderHandle);
public static native int getEncoderEncodingScale(int encoderHandle);
diff --git a/hal/src/main/java/edu/wpi/first/hal/HAL.java b/hal/src/main/java/edu/wpi/first/hal/HAL.java
index 53198e0d8d..5a63d50abd 100644
--- a/hal/src/main/java/edu/wpi/first/hal/HAL.java
+++ b/hal/src/main/java/edu/wpi/first/hal/HAL.java
@@ -12,7 +12,6 @@ import java.util.List;
* JNI Wrapper for HAL
* .
*/
-@SuppressWarnings({"AbbreviationAsWordInName", "MethodName"})
public final class HAL extends JNIWrapper {
public static native void waitForDSData();
@@ -153,7 +152,11 @@ public final class HAL extends JNIWrapper {
public static native int nativeGetControlWord();
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Get the current DriverStation control word.
+ *
+ * @param controlWord Storage for control word.
+ */
public static void getControlWord(ControlWord controlWord) {
int word = nativeGetControlWord();
controlWord.update(
@@ -167,7 +170,11 @@ public final class HAL extends JNIWrapper {
private static native int nativeGetAllianceStation();
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Get the alliance station.
+ *
+ * @return The alliance station.
+ */
public static AllianceStationID getAllianceStation() {
switch (nativeGetAllianceStation()) {
case 0:
@@ -187,13 +194,10 @@ public final class HAL extends JNIWrapper {
}
}
- @SuppressWarnings("MissingJavadocMethod")
public static native boolean isNewControlData();
- @SuppressWarnings("MissingJavadocMethod")
public static native void releaseDSMutex();
- @SuppressWarnings("MissingJavadocMethod")
public static native boolean waitForDSDataTimeout(double timeout);
public static final int kMaxJoystickAxes = 12;
diff --git a/hal/src/main/java/edu/wpi/first/hal/HALUtil.java b/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
index 4da20a22e2..6a672aaa0b 100644
--- a/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
+++ b/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public final class HALUtil extends JNIWrapper {
public static final int NULL_PARAMETER = -1005;
public static final int SAMPLE_RATE_TOO_HIGH = 1001;
diff --git a/hal/src/main/java/edu/wpi/first/hal/HALValue.java b/hal/src/main/java/edu/wpi/first/hal/HALValue.java
index ded57def33..5f5441c03d 100644
--- a/hal/src/main/java/edu/wpi/first/hal/HALValue.java
+++ b/hal/src/main/java/edu/wpi/first/hal/HALValue.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public final class HALValue {
public static final int kUnassigned = 0;
public static final int kBoolean = 0x01;
diff --git a/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java b/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
index 821c89bccc..63f32a0bf5 100644
--- a/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
@@ -6,7 +6,6 @@ package edu.wpi.first.hal;
import java.nio.ByteBuffer;
-@SuppressWarnings("AbbreviationAsWordInName")
public class I2CJNI extends JNIWrapper {
public static native void i2CInitialize(int port);
diff --git a/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java b/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
index 6737c581d6..699ecc59fd 100644
--- a/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
+++ b/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
@@ -5,25 +5,21 @@
package edu.wpi.first.hal;
/** Structure for holding the match info data request. */
+@SuppressWarnings("MemberName")
public class MatchInfoData {
/** Stores the event name. */
- @SuppressWarnings("MemberName")
public String eventName = "";
/** Stores the game specific message. */
- @SuppressWarnings("MemberName")
public String gameSpecificMessage = "";
/** Stores the match number. */
- @SuppressWarnings("MemberName")
public int matchNumber;
/** Stores the replay number. */
- @SuppressWarnings("MemberName")
public int replayNumber;
/** Stores the match type. */
- @SuppressWarnings("MemberName")
public int matchType;
/**
@@ -35,7 +31,6 @@ public class MatchInfoData {
* @param replayNumber Replay number.
* @param matchType Match type.
*/
- @SuppressWarnings("MissingJavadocMethod")
public void setData(
String eventName,
String gameSpecificMessage,
diff --git a/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java b/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
index e64d6da7c6..ac3c8f94c1 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
@@ -5,6 +5,7 @@
package edu.wpi.first.hal;
/** Structure for holding the config data result for PWM. */
+@SuppressWarnings("MemberName")
public class PWMConfigDataResult {
PWMConfigDataResult(int max, int deadbandMax, int center, int deadbandMin, int min) {
this.max = max;
@@ -15,22 +16,17 @@ public class PWMConfigDataResult {
}
/** The maximum PWM value. */
- @SuppressWarnings("MemberName")
public int max;
/** The deadband maximum PWM value. */
- @SuppressWarnings("MemberName")
public int deadbandMax;
/** The center PWM value. */
- @SuppressWarnings("MemberName")
public int center;
/** The deadband minimum PWM value. */
- @SuppressWarnings("MemberName")
public int deadbandMin;
/** The minimum PWM value. */
- @SuppressWarnings("MemberName")
public int min;
}
diff --git a/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java b/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
index 946ad0757b..1ed562c425 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class PWMJNI extends DIOJNI {
public static native int initializePWMPort(int halPortHandle);
diff --git a/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java b/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
index 6a06ff909b..b4bd6cf082 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class PortsJNI extends JNIWrapper {
public static native int getNumAccumulators();
diff --git a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java
index bdff5993c9..aa2cac5b6b 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionFaults.java
@@ -4,86 +4,60 @@
package edu.wpi.first.hal;
+@SuppressWarnings("MemberName")
public class PowerDistributionFaults {
- @SuppressWarnings("MemberName")
public final boolean Channel0BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel1BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel2BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel3BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel4BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel5BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel6BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel7BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel8BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel9BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel10BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel11BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel12BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel13BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel14BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel15BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel16BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel17BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel18BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel19BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel20BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel21BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel22BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel23BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Brownout;
- @SuppressWarnings("MemberName")
public final boolean CanWarning;
- @SuppressWarnings("MemberName")
public final boolean HardwareFault;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java
index 00c4dd1d80..8280f93a07 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class PowerDistributionJNI extends JNIWrapper {
public static final int AUTOMATIC_TYPE = 0;
public static final int CTRE_TYPE = 1;
diff --git a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java
index 0eb4a69084..f60f8df910 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionStickyFaults.java
@@ -4,89 +4,62 @@
package edu.wpi.first.hal;
+@SuppressWarnings("MemberName")
public class PowerDistributionStickyFaults {
- @SuppressWarnings("MemberName")
public final boolean Channel0BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel1BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel2BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel3BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel4BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel5BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel6BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel7BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel8BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel9BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel10BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel11BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel12BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel13BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel14BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel15BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel16BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel17BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel18BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel19BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel20BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel21BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel22BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Channel23BreakerFault;
- @SuppressWarnings("MemberName")
public final boolean Brownout;
- @SuppressWarnings("MemberName")
public final boolean CanWarning;
- @SuppressWarnings("MemberName")
public final boolean CanBusOff;
- @SuppressWarnings("MemberName")
public final boolean HasReset;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java
index 0c733a2303..fdd1233b25 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PowerDistributionVersion.java
@@ -4,23 +4,18 @@
package edu.wpi.first.hal;
+@SuppressWarnings("MemberName")
public class PowerDistributionVersion {
- @SuppressWarnings("MemberName")
public final int firmwareMajor;
- @SuppressWarnings("MemberName")
public final int firmwareMinor;
- @SuppressWarnings("MemberName")
public final int firmwareFix;
- @SuppressWarnings("MemberName")
public final int hardwareMinor;
- @SuppressWarnings("MemberName")
public final int hardwareMajor;
- @SuppressWarnings("MemberName")
public final int uniqueId;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java b/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java
index f71ef698b0..341981051d 100644
--- a/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java
+++ b/hal/src/main/java/edu/wpi/first/hal/REVPHFaults.java
@@ -4,72 +4,50 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MemberName")
public class REVPHFaults {
- @SuppressWarnings("MemberName")
public final boolean Channel0Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel1Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel2Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel3Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel4Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel5Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel6Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel7Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel8Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel9Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel10Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel11Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel12Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel13Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel14Fault;
- @SuppressWarnings("MemberName")
public final boolean Channel15Fault;
- @SuppressWarnings("MemberName")
public final boolean CompressorOverCurrent;
- @SuppressWarnings("MemberName")
public final boolean CompressorOpen;
- @SuppressWarnings("MemberName")
public final boolean SolenoidOverCurrent;
- @SuppressWarnings("MemberName")
public final boolean Brownout;
- @SuppressWarnings("MemberName")
public final boolean CanWarning;
- @SuppressWarnings("MemberName")
public final boolean HardwareFault;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java b/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java
index 17f0323ff3..44c67a80ff 100644
--- a/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/REVPHJNI.java
@@ -4,7 +4,6 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
public class REVPHJNI extends JNIWrapper {
public static final int COMPRESSOR_CONFIG_TYPE_DISABLED = 0;
public static final int COMPRESSOR_CONFIG_TYPE_DIGITAL = 1;
diff --git a/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java b/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java
index 6bf9f4fe1c..614389eabe 100644
--- a/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java
+++ b/hal/src/main/java/edu/wpi/first/hal/REVPHStickyFaults.java
@@ -4,27 +4,20 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MemberName")
public class REVPHStickyFaults {
- @SuppressWarnings("MemberName")
public final boolean CompressorOverCurrent;
- @SuppressWarnings("MemberName")
public final boolean CompressorOpen;
- @SuppressWarnings("MemberName")
public final boolean SolenoidOverCurrent;
- @SuppressWarnings("MemberName")
public final boolean Brownout;
- @SuppressWarnings("MemberName")
public final boolean CanWarning;
- @SuppressWarnings("MemberName")
public final boolean CanBusOff;
- @SuppressWarnings("MemberName")
public final boolean HasReset;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java b/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java
index 13471e7211..86d0743e54 100644
--- a/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java
+++ b/hal/src/main/java/edu/wpi/first/hal/REVPHVersion.java
@@ -4,24 +4,18 @@
package edu.wpi.first.hal;
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MemberName")
public class REVPHVersion {
- @SuppressWarnings("MemberName")
public final int firmwareMajor;
- @SuppressWarnings("MemberName")
public final int firmwareMinor;
- @SuppressWarnings("MemberName")
public final int firmwareFix;
- @SuppressWarnings("MemberName")
public final int hardwareMinor;
- @SuppressWarnings("MemberName")
public final int hardwareMajor;
- @SuppressWarnings("MemberName")
public final int uniqueId;
/**
diff --git a/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java b/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
index 0652c3fa4a..053f1929cc 100644
--- a/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
@@ -6,7 +6,6 @@ package edu.wpi.first.hal;
import java.nio.ByteBuffer;
-@SuppressWarnings("AbbreviationAsWordInName")
public class SPIJNI extends JNIWrapper {
public static final int INVALID_PORT = -1;
public static final int ONBOARD_CS0_PORT = 0;
diff --git a/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java b/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
index b4f344fd6f..6a498a6faf 100644
--- a/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
@@ -8,7 +8,7 @@ import edu.wpi.first.hal.JNIWrapper;
import java.nio.ByteBuffer;
import java.nio.IntBuffer;
-@SuppressWarnings("AbbreviationAsWordInName")
+@SuppressWarnings("MethodName")
public class CANJNI extends JNIWrapper {
public static final int CAN_SEND_PERIOD_NO_REPEAT = 0;
public static final int CAN_SEND_PERIOD_STOP_REPEATING = -1;
@@ -17,14 +17,11 @@ public class CANJNI extends JNIWrapper {
public static final int CAN_IS_FRAME_REMOTE = 0x80000000;
public static final int CAN_IS_FRAME_11BIT = 0x40000000;
- @SuppressWarnings("MethodName")
public static native void FRCNetCommCANSessionMuxSendMessage(
int messageID, byte[] data, int periodMs);
- @SuppressWarnings("MethodName")
public static native byte[] FRCNetCommCANSessionMuxReceiveMessage(
IntBuffer messageID, int messageIDMask, ByteBuffer timeStamp);
- @SuppressWarnings("MethodName")
public static native void getCANStatus(CANStatus status);
}
diff --git a/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java b/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
index 62df8e8e19..8ec89f74a2 100644
--- a/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
+++ b/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
@@ -5,28 +5,32 @@
package edu.wpi.first.hal.can;
/** Structure for holding the result of a CAN Status request. */
+@SuppressWarnings("MemberName")
public class CANStatus {
/** The utilization of the CAN Bus. */
- @SuppressWarnings("MemberName")
public double percentBusUtilization;
/** The CAN Bus off count. */
- @SuppressWarnings("MemberName")
public int busOffCount;
/** The CAN Bus TX full count. */
- @SuppressWarnings("MemberName")
public int txFullCount;
/** The CAN Bus receive error count. */
- @SuppressWarnings("MemberName")
public int receiveErrorCount;
/** The CAN Bus transmit error count. */
- @SuppressWarnings("MemberName")
public int transmitErrorCount;
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * Set CAN bus status.
+ *
+ * @param percentBusUtilization CAN bus utilization as a percent.
+ * @param busOffCount Bus off event count.
+ * @param txFullCount TX buffer full event count.
+ * @param receiveErrorCount Receive error event count.
+ * @param transmitErrorCount Transmit error event count.
+ */
public void setStatus(
double percentBusUtilization,
int busOffCount,
diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java
index 9f60e7e245..6d94438d99 100644
--- a/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/simulation/CTREPCMDataJNI.java
@@ -6,7 +6,6 @@ package edu.wpi.first.hal.simulation;
import edu.wpi.first.hal.JNIWrapper;
-@SuppressWarnings("AbbreviationAsWordInName")
public class CTREPCMDataJNI extends JNIWrapper {
public static native int registerInitializedCallback(
int index, NotifyCallback callback, boolean initialNotify);
diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java
index ee801f3a23..96b9701c27 100644
--- a/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/simulation/REVPHDataJNI.java
@@ -6,7 +6,6 @@ package edu.wpi.first.hal.simulation;
import edu.wpi.first.hal.JNIWrapper;
-@SuppressWarnings("AbbreviationAsWordInName")
public class REVPHDataJNI extends JNIWrapper {
public static native int registerInitializedCallback(
int index, NotifyCallback callback, boolean initialNotify);
diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java
index a822ede7ed..16309be341 100644
--- a/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/simulation/RoboRioDataJNI.java
@@ -7,17 +7,13 @@ package edu.wpi.first.hal.simulation;
import edu.wpi.first.hal.JNIWrapper;
public class RoboRioDataJNI extends JNIWrapper {
- @SuppressWarnings("AbbreviationAsWordInName")
public static native int registerFPGAButtonCallback(
NotifyCallback callback, boolean initialNotify);
- @SuppressWarnings("AbbreviationAsWordInName")
public static native void cancelFPGAButtonCallback(int uid);
- @SuppressWarnings("AbbreviationAsWordInName")
public static native boolean getFPGAButton();
- @SuppressWarnings("AbbreviationAsWordInName")
public static native void setFPGAButton(boolean fPGAButton);
public static native int registerVInVoltageCallback(
diff --git a/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java
index d3b56e1d66..092b955dc6 100644
--- a/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/simulation/SimDeviceDataJNI.java
@@ -28,18 +28,21 @@ public class SimDeviceDataJNI extends JNIWrapper {
public static native int getSimValueDeviceHandle(int handle);
+ @SuppressWarnings("MemberName")
public static class SimDeviceInfo {
- @SuppressWarnings("JavadocMethod")
+ public String name;
+ public int handle;
+
+ /**
+ * SimDeviceInfo constructor.
+ *
+ * @param name SimDevice name.
+ * @param handle SimDevice handle.
+ */
public SimDeviceInfo(String name, int handle) {
this.name = name;
this.handle = handle;
}
-
- @SuppressWarnings("MemberName")
- public String name;
-
- @SuppressWarnings("MemberName")
- public int handle;
}
public static native SimDeviceInfo[] enumerateSimDevices(String prefix);
@@ -70,8 +73,23 @@ public class SimDeviceDataJNI extends JNIWrapper {
public static native int getSimValueHandle(int device, String name);
+ @SuppressWarnings("MemberName")
public static class SimValueInfo {
- @SuppressWarnings("JavadocMethod")
+ public String name;
+ public int handle;
+ public int direction;
+ public HALValue value;
+
+ /**
+ * SimValueInfo constructor.
+ *
+ * @param name SimValue name.
+ * @param handle SimValue handle.
+ * @param direction SimValue direction.
+ * @param type SimValue type.
+ * @param value1 Value 1.
+ * @param value2 Value 2.
+ */
public SimValueInfo(
String name, int handle, int direction, int type, long value1, double value2) {
this.name = name;
@@ -79,18 +97,6 @@ public class SimDeviceDataJNI extends JNIWrapper {
this.direction = direction;
this.value = HALValue.fromNative(type, value1, value2);
}
-
- @SuppressWarnings("MemberName")
- public String name;
-
- @SuppressWarnings("MemberName")
- public int handle;
-
- @SuppressWarnings("MemberName")
- public int direction;
-
- @SuppressWarnings("MemberName")
- public HALValue value;
}
public static native SimValueInfo[] enumerateSimValues(int device);
diff --git a/myRobot/src/main/java/frc/robot/MyRobot.java b/myRobot/src/main/java/frc/robot/MyRobot.java
index e62c34580b..a5f88bd3f3 100644
--- a/myRobot/src/main/java/frc/robot/MyRobot.java
+++ b/myRobot/src/main/java/frc/robot/MyRobot.java
@@ -6,7 +6,6 @@ package frc.robot;
import edu.wpi.first.wpilibj.TimedRobot;
-@SuppressWarnings("all")
public class MyRobot extends TimedRobot {
/**
* This function is run when the robot is first started up and should be used for any
@@ -15,27 +14,27 @@ public class MyRobot extends TimedRobot {
@Override
public void robotInit() {}
- /** This function is run once each time the robot enters autonomous mode */
+ /** This function is run once each time the robot enters autonomous mode. */
@Override
public void autonomousInit() {}
- /** This function is called periodically during autonomous */
+ /** This function is called periodically during autonomous. */
@Override
public void autonomousPeriodic() {}
- /** This function is called once each time the robot enters tele-operated mode */
+ /** This function is called once each time the robot enters tele-operated mode. */
@Override
public void teleopInit() {}
- /** This function is called periodically during operator control */
+ /** This function is called periodically during operator control. */
@Override
public void teleopPeriodic() {}
- /** This function is called periodically during test mode */
+ /** This function is called periodically during test mode. */
@Override
public void testPeriodic() {}
- /** This function is called periodically during all modes */
+ /** This function is called periodically during all modes. */
@Override
public void robotPeriodic() {}
}
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java b/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
index 477d53bcb7..e043a30a05 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
@@ -5,34 +5,30 @@
package edu.wpi.first.networktables;
/** NetworkTables Connection information. */
+@SuppressWarnings("MemberName")
public final class ConnectionInfo {
/**
* The remote identifier (as set on the remote node by {@link
* NetworkTableInstance#setNetworkIdentity(String)}).
*/
- @SuppressWarnings("MemberName")
public final String remote_id;
/** The IP address of the remote node. */
- @SuppressWarnings("MemberName")
public final String remote_ip;
/** The port number of the remote node. */
- @SuppressWarnings("MemberName")
public final int remote_port;
/**
* The last time any update was received from the remote node (same scale as returned by {@link
* NetworkTablesJNI#now()}).
*/
- @SuppressWarnings("MemberName")
public final long last_update;
/**
* The protocol version being used for this connection. This is in protocol layer format, so
* 0x0200 = 2.0, 0x0300 = 3.0).
*/
- @SuppressWarnings("MemberName")
public final int protocol_version;
/**
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java b/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java
index 544e075671..cd031dafe5 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java
@@ -5,17 +5,15 @@
package edu.wpi.first.networktables;
/** NetworkTables Connection notification. */
+@SuppressWarnings("MemberName")
public final class ConnectionNotification {
/** Listener that was triggered. */
- @SuppressWarnings("MemberName")
public final int listener;
/** True if event is due to connection being established. */
- @SuppressWarnings("MemberName")
public final boolean connected;
/** Connection information. */
- @SuppressWarnings("MemberName")
public final ConnectionInfo conn;
/**
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java b/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java
index 471edc8a11..bdcc6deaeb 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java
@@ -5,25 +5,21 @@
package edu.wpi.first.networktables;
/** NetworkTables Entry information. */
+@SuppressWarnings("MemberName")
public final class EntryInfo {
/** Entry handle. */
- @SuppressWarnings("MemberName")
public final int entry;
/** Entry name. */
- @SuppressWarnings("MemberName")
public final String name;
/** Entry type. */
- @SuppressWarnings("MemberName")
public final NetworkTableType type;
/** Entry flags. */
- @SuppressWarnings("MemberName")
public final int flags;
/** Timestamp of last change to entry (type or value). */
- @SuppressWarnings("MemberName")
public final long last_change;
/**
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java b/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java
index 0f5cb51180..a957cf73d4 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java
@@ -5,27 +5,23 @@
package edu.wpi.first.networktables;
/** NetworkTables Entry notification. */
+@SuppressWarnings("MemberName")
public final class EntryNotification {
/** Listener that was triggered. */
- @SuppressWarnings("MemberName")
public final int listener;
/** Entry handle. */
- @SuppressWarnings("MemberName")
public final int entry;
/** Entry name. */
- @SuppressWarnings("MemberName")
public final String name;
/** The new value. */
- @SuppressWarnings("MemberName")
public final NetworkTableValue value;
/**
* Update flags. For example, {@link EntryListenerFlags#kNew} if the key did not previously exist.
*/
- @SuppressWarnings("MemberName")
public final int flags;
/**
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java b/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
index 5d77d8b877..8ed653dcb9 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
@@ -5,6 +5,7 @@
package edu.wpi.first.networktables;
/** NetworkTables log message. */
+@SuppressWarnings("MemberName")
public final class LogMessage {
/** Logging levels. */
public static final int kCritical = 50;
@@ -19,23 +20,18 @@ public final class LogMessage {
public static final int kDebug4 = 6;
/** The logger that generated the message. */
- @SuppressWarnings("MemberName")
public final int logger;
/** Log level of the message. */
- @SuppressWarnings("MemberName")
public final int level;
/** The filename of the source file that generated the message. */
- @SuppressWarnings("MemberName")
public final String filename;
/** The line number in the source file that generated the message. */
- @SuppressWarnings("MemberName")
public final int line;
/** The message. */
- @SuppressWarnings("MemberName")
public final String message;
/**
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java b/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java
index f3ff37b4e2..53ed3e03c0 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java
@@ -207,7 +207,6 @@ public final class NetworkTableInstance implements AutoCloseable {
private boolean m_entryListenerWaitQueue;
private final Condition m_entryListenerWaitQueueCond = m_entryListenerLock.newCondition();
- @SuppressWarnings("PMD.AvoidCatchingThrowable")
private void startEntryListenerThread() {
var entryListenerThread =
new Thread(
@@ -375,7 +374,6 @@ public final class NetworkTableInstance implements AutoCloseable {
private final Condition m_connectionListenerWaitQueueCond =
m_connectionListenerLock.newCondition();
- @SuppressWarnings("PMD.AvoidCatchingThrowable")
private void startConnectionListenerThread() {
var connectionListenerThread =
new Thread(
@@ -524,7 +522,6 @@ public final class NetworkTableInstance implements AutoCloseable {
private boolean m_rpcCallWaitQueue;
private final Condition m_rpcCallWaitQueueCond = m_rpcCallLock.newCondition();
- @SuppressWarnings("PMD.AvoidCatchingThrowable")
private void startRpcCallThread() {
var rpcCallThread =
new Thread(
@@ -1048,7 +1045,6 @@ public final class NetworkTableInstance implements AutoCloseable {
private boolean m_loggerWaitQueue;
private final Condition m_loggerWaitQueueCond = m_loggerLock.newCondition();
- @SuppressWarnings("PMD.AvoidCatchingThrowable")
private void startLogThread() {
var loggerThread =
new Thread(
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java b/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java
index f4b929048d..0c4c1ef804 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java
@@ -7,6 +7,7 @@ package edu.wpi.first.networktables;
import java.util.Objects;
/** A network table entry value. */
+@SuppressWarnings("PMD.MethodReturnsInternalArray")
public final class NetworkTableValue {
NetworkTableValue(NetworkTableType type, Object value, long time) {
m_type = type;
@@ -183,7 +184,6 @@ public final class NetworkTableValue {
* @return The raw value.
* @throws ClassCastException if the entry value is not of raw type.
*/
- @SuppressWarnings("PMD.MethodReturnsInternalArray")
public byte[] getRaw() {
if (m_type != NetworkTableType.kRaw) {
throw new ClassCastException("cannot convert " + m_type + " to raw");
@@ -197,7 +197,6 @@ public final class NetworkTableValue {
* @return The rpc definition value.
* @throws ClassCastException if the entry value is not of rpc definition type.
*/
- @SuppressWarnings("PMD.MethodReturnsInternalArray")
public byte[] getRpc() {
if (m_type != NetworkTableType.kRpc) {
throw new ClassCastException("cannot convert " + m_type + " to rpc");
@@ -211,7 +210,6 @@ public final class NetworkTableValue {
* @return The boolean array value.
* @throws ClassCastException if the entry value is not of boolean array type.
*/
- @SuppressWarnings("PMD.MethodReturnsInternalArray")
public boolean[] getBooleanArray() {
if (m_type != NetworkTableType.kBooleanArray) {
throw new ClassCastException("cannot convert " + m_type + " to boolean array");
@@ -225,7 +223,6 @@ public final class NetworkTableValue {
* @return The double array value.
* @throws ClassCastException if the entry value is not of double array type.
*/
- @SuppressWarnings("PMD.MethodReturnsInternalArray")
public double[] getDoubleArray() {
if (m_type != NetworkTableType.kDoubleArray) {
throw new ClassCastException("cannot convert " + m_type + " to double array");
@@ -239,7 +236,6 @@ public final class NetworkTableValue {
* @return The string array value.
* @throws ClassCastException if the entry value is not of string array type.
*/
- @SuppressWarnings("PMD.MethodReturnsInternalArray")
public String[] getStringArray() {
if (m_type != NetworkTableType.kStringArray) {
throw new ClassCastException("cannot convert " + m_type + " to string array");
diff --git a/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java b/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java
index a244bdebee..422ad16a5c 100644
--- a/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java
+++ b/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java
@@ -5,25 +5,21 @@
package edu.wpi.first.networktables;
/** NetworkTables Remote Procedure Call (Server Side). */
+@SuppressWarnings("MemberName")
public final class RpcAnswer {
/** Entry handle. */
- @SuppressWarnings("MemberName")
public final int entry;
/** Call handle. */
- @SuppressWarnings("MemberName")
public int call;
/** Entry name. */
- @SuppressWarnings("MemberName")
public final String name;
/** Call raw parameters. */
- @SuppressWarnings("MemberName")
public final byte[] params;
/** Connection that called the RPC. */
- @SuppressWarnings("MemberName")
public final ConnectionInfo conn;
/**
diff --git a/styleguide/checkstyle-suppressions.xml b/styleguide/checkstyle-suppressions.xml
index 54d4c2bce8..9a66026c06 100644
--- a/styleguide/checkstyle-suppressions.xml
+++ b/styleguide/checkstyle-suppressions.xml
@@ -6,6 +6,8 @@ suppressions PUBLIC "-//Puppy Crawl//DTD Suppressions 1.1//EN"
+
+ checks="(EmptyLineSeparator|LineLength|MissingJavadocMethod|ParameterName)" />
diff --git a/styleguide/checkstyle.xml b/styleguide/checkstyle.xml
index 4b35df8fa5..db0f60693a 100644
--- a/styleguide/checkstyle.xml
+++ b/styleguide/checkstyle.xml
@@ -170,19 +170,19 @@ module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN"
+ value="^(m_([a-zA-Z]|[a-z][a-zA-Z0-9]+)|value)$" />
+ value="^([a-zA-Z]|[a-z][a-zA-Z0-9]+)$" />
+ value="^(_?[a-zA-Z]|_?[a-z][a-zA-Z0-9]+)$" />
@@ -195,26 +195,23 @@ module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN"
+ value="^([a-zA-Z][0-9]*|[a-z][a-zA-Z0-9]+)$" />
-
+
-
+
-
+
@@ -229,10 +226,6 @@ module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN"
-
-
-
-
diff --git a/styleguide/pmd-ruleset.xml b/styleguide/pmd-ruleset.xml
index 0f37af0871..54a4881cd2 100644
--- a/styleguide/pmd-ruleset.xml
+++ b/styleguide/pmd-ruleset.xml
@@ -13,15 +13,18 @@
+
+
+
@@ -58,6 +61,7 @@
+
@@ -65,6 +69,8 @@
+
+
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 18c2a378c1..4c10b3edd0 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
@@ -38,7 +38,6 @@ import java.util.function.Supplier;
*
* This class is provided by the NewCommands VendorDep
*/
-@SuppressWarnings("MemberName")
public class MecanumControllerCommand extends CommandBase {
private final Timer m_timer = new Timer();
private final boolean m_usePID;
@@ -87,7 +86,6 @@ public class MecanumControllerCommand extends CommandBase {
* voltages.
* @param requirements The subsystems to require.
*/
- @SuppressWarnings("ParameterName")
public MecanumControllerCommand(
Trajectory trajectory,
Supplier pose,
@@ -179,7 +177,6 @@ public class MecanumControllerCommand extends CommandBase {
* voltages.
* @param requirements The subsystems to require.
*/
- @SuppressWarnings("ParameterName")
public MecanumControllerCommand(
Trajectory trajectory,
Supplier pose,
@@ -236,7 +233,6 @@ public class MecanumControllerCommand extends CommandBase {
* @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds.
* @param requirements The subsystems to require.
*/
- @SuppressWarnings("ParameterName")
public MecanumControllerCommand(
Trajectory trajectory,
Supplier pose,
@@ -308,7 +304,6 @@ public class MecanumControllerCommand extends CommandBase {
* @param outputWheelSpeeds A MecanumDriveWheelSpeeds object containing the output wheel speeds.
* @param requirements The subsystems to require.
*/
- @SuppressWarnings("ParameterName")
public MecanumControllerCommand(
Trajectory trajectory,
Supplier pose,
@@ -350,7 +345,6 @@ public class MecanumControllerCommand extends CommandBase {
}
@Override
- @SuppressWarnings("LocalVariableName")
public void execute() {
double curTime = m_timer.get();
double dt = curTime - m_prevTime;
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 58b786b4f3..99e5683708 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
@@ -31,7 +31,6 @@ import java.util.function.Supplier;
*
* This class is provided by the NewCommands VendorDep
*/
-@SuppressWarnings("MemberName")
public class SwerveControllerCommand extends CommandBase {
private final Timer m_timer = new Timer();
private final Trajectory m_trajectory;
@@ -61,7 +60,6 @@ public class SwerveControllerCommand extends CommandBase {
* @param outputModuleStates The raw output module states from the position controllers.
* @param requirements The subsystems to require.
*/
- @SuppressWarnings("ParameterName")
public SwerveControllerCommand(
Trajectory trajectory,
Supplier pose,
@@ -114,7 +112,6 @@ public class SwerveControllerCommand extends CommandBase {
* @param outputModuleStates The raw output module states from the position controllers.
* @param requirements The subsystems to require.
*/
- @SuppressWarnings("ParameterName")
public SwerveControllerCommand(
Trajectory trajectory,
Supplier pose,
@@ -144,7 +141,6 @@ public class SwerveControllerCommand extends CommandBase {
}
@Override
- @SuppressWarnings("LocalVariableName")
public void execute() {
double curTime = m_timer.get();
var desiredState = m_trajectory.sample(curTime);
diff --git a/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h b/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
index 03cc4f8705..575cf3e503 100644
--- a/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
+++ b/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
@@ -21,6 +21,9 @@ class DigitalSource;
*/
class SynchronousInterrupt {
public:
+ /**
+ * Event trigger combinations for a synchronous interrupt.
+ */
enum WaitResult {
kTimeout = 0x0,
kRisingEdge = 0x1,
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 cbb43e8545..20b34766bc 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
@@ -611,7 +611,6 @@ public class ADIS16448_IMU implements AutoCloseable, NTSendable {
m_spi.write(buf, 2);
}
- /** {@inheritDoc} */
public void reset() {
synchronized (this) {
m_integ_gyro_angle_x = 0.0;
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 b0f90c91bd..95b14f8166 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
@@ -636,7 +636,6 @@ public class ADIS16470_IMU implements AutoCloseable, NTSendable {
m_spi.write(buf, 2);
}
- /** {@inheritDoc} */
public void reset() {
synchronized (this) {
m_integ_angle = 0.0;
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 03c81d5524..13fe85c46c 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
@@ -49,7 +49,6 @@ public class ADXL345_I2C implements Accelerometer, NTSendable, AutoCloseable {
kZ((byte) 0x04);
/** The integer value representing this enumeration. */
- @SuppressWarnings("MemberName")
public final byte value;
Axes(byte value) {
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 e12d8b9270..145e6e215a 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
@@ -26,7 +26,7 @@ import java.nio.ByteOrder;
* This class is for the digital ADXRS450 gyro sensor that connects via SPI. Only one instance of
* an ADXRS Gyro is supported.
*/
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName", "PMD.UnusedPrivateField"})
+@SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"})
public class ADXRS450_Gyro implements Gyro, Sendable {
private static final double kSamplePeriod = 0.0005;
private static final double kCalibrationSampleTime = 5.0;
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java
index c9659a131a..e02958aaf0 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/AddressableLEDBuffer.java
@@ -28,7 +28,6 @@ public class AddressableLEDBuffer {
* @param g the g value [0-255]
* @param b the b value [0-255]
*/
- @SuppressWarnings("ParameterName")
public void setRGB(int index, int r, int g, int b) {
m_buffer[index * 4] = (byte) b;
m_buffer[(index * 4) + 1] = (byte) g;
@@ -44,7 +43,6 @@ public class AddressableLEDBuffer {
* @param s the s value [0-255]
* @param v the v value [0-255]
*/
- @SuppressWarnings("ParameterName")
public void setHSV(final int index, final int h, final int s, final int v) {
if (s == 0) {
setRGB(index, v, v, v);
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 d445e9f537..124676a10e 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
@@ -192,7 +192,6 @@ public class Counter implements CounterBase, Sendable, AutoCloseable {
*
* @return the Counter's FPGA index
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public int getFPGAIndex() {
return m_index;
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java
index d1d3db03e6..42d6be0d41 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DataLogManager.java
@@ -188,7 +188,6 @@ public final class DataLogManager {
}
}
- @SuppressWarnings("PMD.EmptyCatchBlock")
private static String makeLogDir(String dir) {
if (!dir.isEmpty()) {
return dir;
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
index 14b7350935..be3c20717e 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
@@ -80,59 +80,25 @@ public final class DriverStation {
}
} /* DriverStationTask */
+ @SuppressWarnings("MemberName")
private static class MatchDataSender {
- @SuppressWarnings("MemberName")
NetworkTable table;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry typeMetadata;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry gameSpecificMessage;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry eventName;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry matchNumber;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry replayNumber;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry matchType;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry alliance;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry station;
-
- @SuppressWarnings("MemberName")
NetworkTableEntry controlWord;
-
- @SuppressWarnings("MemberName")
boolean oldIsRedAlliance = true;
-
- @SuppressWarnings("MemberName")
int oldStationNumber = 1;
-
- @SuppressWarnings("MemberName")
String oldEventName = "";
-
- @SuppressWarnings("MemberName")
String oldGameSpecificMessage = "";
-
- @SuppressWarnings("MemberName")
int oldMatchNumber;
-
- @SuppressWarnings("MemberName")
int oldReplayNumber;
-
- @SuppressWarnings("MemberName")
int oldMatchType;
-
- @SuppressWarnings("MemberName")
int oldControlWord;
MatchDataSender() {
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 c700bca07e..7cd6cba483 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycle.java
@@ -100,7 +100,6 @@ public class DutyCycle implements Sendable, AutoCloseable {
*
* @return the FPGA index
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public final int getFPGAIndex() {
return DutyCycleJNI.getFPGAIndex(m_handle);
}
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 d0cfe8bbba..fc097a1e0b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DutyCycleEncoder.java
@@ -299,7 +299,6 @@ public class DutyCycleEncoder implements Sendable, AutoCloseable {
*
* @return the FPGA index
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public int getFPGAIndex() {
return m_dutyCycle.getFPGAIndex();
}
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 01965b4787..7a5ea61f49 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java
@@ -282,7 +282,6 @@ public class Encoder implements CounterBase, Sendable, AutoCloseable {
*
* @return The Encoder's FPGA index.
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public int getFPGAIndex() {
return EncoderJNI.getEncoderFPGAIndex(m_encoder);
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
index f4bce1132a..830ad30115 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
@@ -116,7 +116,6 @@ public class I2C implements AutoCloseable {
* @param receiveSize Number of bytes to read from the device.
* @return Transfer Aborted... false for success, true for aborted.
*/
- @SuppressWarnings("ByteBufferBackingArray")
public synchronized boolean transaction(
ByteBuffer dataToSend, int sendSize, ByteBuffer dataReceived, int receiveSize) {
if (dataToSend.hasArray() && dataReceived.hasArray()) {
@@ -211,7 +210,6 @@ public class I2C implements AutoCloseable {
* @param size The number of data bytes to write.
* @return Transfer Aborted... false for success, true for aborted.
*/
- @SuppressWarnings("ByteBufferBackingArray")
public synchronized boolean writeBulk(ByteBuffer data, int size) {
if (data.hasArray()) {
return writeBulk(data.array(), size);
@@ -266,7 +264,6 @@ public class I2C implements AutoCloseable {
* @param buffer A buffer to store the data read from the device.
* @return Transfer Aborted... false for success, true for aborted.
*/
- @SuppressWarnings("ByteBufferBackingArray")
public boolean read(int registerAddress, int count, ByteBuffer buffer) {
if (count < 1) {
throw new BoundaryException("Value must be at least 1, " + count + " given");
@@ -323,7 +320,6 @@ public class I2C implements AutoCloseable {
* @param count The number of bytes to read in the transaction.
* @return Transfer Aborted... false for success, true for aborted.
*/
- @SuppressWarnings("ByteBufferBackingArray")
public boolean readOnly(ByteBuffer buffer, int count) {
if (count < 1) {
throw new BoundaryException("Value must be at least 1, " + count + " given");
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
index 2749964475..d314830bcf 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
@@ -134,7 +134,6 @@ public abstract class IterativeRobotBase extends RobotBase {
*
Users should override this method for initialization code which will be called each time the
* robot enters test mode.
*/
- @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
public void testInit() {}
/* ----------- Overridable periodic code ----------------- */
@@ -196,7 +195,6 @@ public abstract class IterativeRobotBase extends RobotBase {
private boolean m_tmpFirstRun = true;
/** Periodic code for test mode should go here. */
- @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
public void testPeriodic() {
if (m_tmpFirstRun) {
System.out.println("Default testPeriodic() method... Override me!");
@@ -234,7 +232,6 @@ public abstract class IterativeRobotBase extends RobotBase {
*
Users should override this method for code which will be called each time the robot exits
* test mode.
*/
- @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
public void testExit() {}
/**
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 53b58a1547..78e4d46feb 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
@@ -269,27 +269,11 @@ public abstract class RobotBase implements AutoCloseable {
/** Ends the main loop in startCompetition(). */
public abstract void endCompetition();
- @SuppressWarnings("MissingJavadocMethod")
- public static boolean getBooleanProperty(String name, boolean defaultValue) {
- String propVal = System.getProperty(name);
- if (propVal == null) {
- return defaultValue;
- }
- if ("false".equalsIgnoreCase(propVal)) {
- return false;
- } else if ("true".equalsIgnoreCase(propVal)) {
- return true;
- } else {
- throw new IllegalStateException(propVal);
- }
- }
-
private static final ReentrantLock m_runMutex = new ReentrantLock();
private static RobotBase m_robotCopy;
private static boolean m_suppressExitWarning;
/** Run the robot main loop. */
- @SuppressWarnings({"PMD.AvoidCatchingThrowable", "PMD.AvoidReassigningCatchVariables"})
private static void runRobot(Supplier robotSupplier) {
System.out.println("********** Robot program starting **********");
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
index 8a7460eafe..c0d2705b4b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
@@ -21,7 +21,6 @@ public final class RobotController {
*
* @return FPGA Version number.
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static int getFPGAVersion() {
return HALUtil.getFPGAVersion();
}
@@ -33,7 +32,6 @@ public final class RobotController {
*
* @return FPGA Revision number.
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static long getFPGARevision() {
return (long) HALUtil.getFPGARevision();
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
index 8020a75ce8..44198df1a1 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
@@ -4,28 +4,57 @@
package edu.wpi.first.wpilibj;
-@SuppressWarnings("MissingJavadocMethod")
public final class RobotState {
+ /**
+ * Returns true if the robot is disabled.
+ *
+ * @return True if the robot is disabled.
+ */
public static boolean isDisabled() {
return DriverStation.isDisabled();
}
+ /**
+ * Returns true if the robot is enabled.
+ *
+ * @return True if the robot is enabled.
+ */
public static boolean isEnabled() {
return DriverStation.isEnabled();
}
+ /**
+ * Returns true if the robot is E-stopped.
+ *
+ * @return True if the robot is E-stopped.
+ */
public static boolean isEStopped() {
return DriverStation.isEStopped();
}
+ /**
+ * Returns true if the robot is in teleop mode.
+ *
+ * @return True if the robot is in teleop mode.
+ */
public static boolean isTeleop() {
return DriverStation.isTeleop();
}
+ /**
+ * Returns true if the robot is in autonomous mode.
+ *
+ * @return True if the robot is in autonomous mode.
+ */
public static boolean isAutonomous() {
return DriverStation.isAutonomous();
}
+ /**
+ * Returns true if the robot is in test mode.
+ *
+ * @return True if the robot is in test mode.
+ */
public static boolean isTest() {
return DriverStation.isTest();
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
index f93a9f0b4e..1e4c3e5fda 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
@@ -208,7 +208,6 @@ public class SPI implements AutoCloseable {
* @param size The number of bytes to send.
* @return Number of bytes written or -1 on error.
*/
- @SuppressWarnings("ByteBufferBackingArray")
public int write(ByteBuffer dataToSend, int size) {
if (dataToSend.hasArray()) {
return write(dataToSend.array(), size);
@@ -257,7 +256,6 @@ public class SPI implements AutoCloseable {
* @param size The length of the transaction, in bytes
* @return Number of bytes read or -1 on error.
*/
- @SuppressWarnings("ByteBufferBackingArray")
public int read(boolean initiate, ByteBuffer dataReceived, int size) {
if (dataReceived.hasArray()) {
return read(initiate, dataReceived.array(), size);
@@ -297,7 +295,6 @@ public class SPI implements AutoCloseable {
* @param size The length of the transaction, in bytes
* @return TODO
*/
- @SuppressWarnings("ByteBufferBackingArray")
public int transaction(ByteBuffer dataToSend, ByteBuffer dataReceived, int size) {
if (dataToSend.hasArray() && dataReceived.hasArray()) {
return transaction(dataToSend.array(), dataReceived.array(), size);
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
index 0ac24dee19..bcedd81fea 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
@@ -141,7 +141,6 @@ public final class SensorUtil {
*
* @return The number of the default solenoid module.
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static int getDefaultCTREPCMModule() {
return 0;
}
@@ -151,7 +150,6 @@ public final class SensorUtil {
*
* @return The number of the default solenoid module.
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static int getDefaultREVPHModule() {
return 1;
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
index 1e7a54de7c..ad48b5e5c4 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SynchronousInterrupt.java
@@ -21,14 +21,13 @@ public class SynchronousInterrupt implements AutoCloseable {
private final int m_handle;
- @SuppressWarnings("JavadocMethod")
+ /** Event trigger combinations for a synchronous interrupt. */
public enum WaitResult {
kTimeout(0x0),
kRisingEdge(0x1),
kFallingEdge(0x100),
kBoth(0x101);
- @SuppressWarnings("MemberName")
public final int value;
WaitResult(int value) {
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 bb5ee35612..972df950ed 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
@@ -101,7 +101,6 @@ public class TimedRobot extends IterativeRobotBase {
/** Provide an alternate "main loop" via startCompetition(). */
@Override
- @SuppressWarnings("UnsafeFinalization")
public void startCompetition() {
robotInit();
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 4173479860..6f9a3614f8 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
@@ -17,7 +17,6 @@ public class Timer {
*
* @return Robot running time in seconds.
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static double getFPGATimestamp() {
return RobotController.getFPGATime() / 1000000.0;
}
@@ -55,7 +54,7 @@ public class Timer {
private double m_accumulatedTime;
private boolean m_running;
- @SuppressWarnings("MissingJavadocMethod")
+ /** Timer constructor. */
public Timer() {
reset();
}
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 ea04192d2d..2415079b24 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Tracer.java
@@ -22,7 +22,6 @@ public class Tracer {
private long m_lastEpochsPrintTime; // microseconds
private long m_startTime; // microseconds
- @SuppressWarnings("PMD.UseConcurrentHashMap")
private final Map m_epochs = new HashMap<>(); // microseconds
/** Tracer constructor. */
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
index 22581a56ec..f7bf85b634 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
@@ -208,7 +208,6 @@ public class Watchdog implements Closeable, Comparable {
m_suppressTimeoutMessage = suppress;
}
- @SuppressWarnings("resource")
private static void updateAlarm() {
if (m_watchdogs.size() == 0) {
NotifierJNI.cancelNotifierAlarm(m_notifier);
@@ -225,7 +224,6 @@ public class Watchdog implements Closeable, Comparable {
return inst;
}
- @SuppressWarnings("PMD.AvoidDeeplyNestedIfStmts")
private static void schedulerFunc() {
while (!Thread.currentThread().isInterrupted()) {
long curTime = NotifierJNI.waitForNotifierAlarm(m_notifier);
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
index fdaabfe7b7..d5f0fcc4e7 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
@@ -30,7 +30,6 @@ public class XboxController extends GenericHID {
kBack(7),
kStart(8);
- @SuppressWarnings("MemberName")
public final int value;
Button(int value) {
@@ -64,7 +63,6 @@ public class XboxController extends GenericHID {
kLeftTrigger(2),
kRightTrigger(3);
- @SuppressWarnings("MemberName")
public final int value;
Axis(int value) {
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 c41e44245a..fe846b6a46 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
@@ -155,7 +155,6 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
* positive.
*/
- @SuppressWarnings("ParameterName")
public void arcadeDrive(double xSpeed, double zRotation) {
arcadeDrive(xSpeed, zRotation, true);
}
@@ -168,7 +167,6 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
* positive.
* @param squareInputs If set, decreases the input sensitivity at low speeds.
*/
- @SuppressWarnings("ParameterName")
public void arcadeDrive(double xSpeed, double zRotation, boolean squareInputs) {
if (!m_reported) {
HAL.report(
@@ -198,7 +196,6 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
* @param allowTurnInPlace If set, overrides constant-curvature turning for turn-in-place
* maneuvers. zRotation will control turning rate instead of curvature.
*/
- @SuppressWarnings("ParameterName")
public void curvatureDrive(double xSpeed, double zRotation, boolean allowTurnInPlace) {
if (!m_reported) {
HAL.report(
@@ -264,7 +261,6 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
* @param squareInputs If set, decreases the input sensitivity at low speeds.
* @return Wheel speeds [-1.0..1.0].
*/
- @SuppressWarnings("ParameterName")
public static WheelSpeeds arcadeDriveIK(double xSpeed, double zRotation, boolean squareInputs) {
xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0);
zRotation = MathUtil.clamp(zRotation, -1.0, 1.0);
@@ -323,7 +319,6 @@ public class DifferentialDrive extends RobotDriveBase implements Sendable, AutoC
* maneuvers. zRotation will control rotation rate around the Z axis instead of curvature.
* @return Wheel speeds [-1.0..1.0].
*/
- @SuppressWarnings("ParameterName")
public static WheelSpeeds curvatureDriveIK(
double xSpeed, double zRotation, boolean allowTurnInPlace) {
xSpeed = MathUtil.clamp(xSpeed, -1.0, 1.0);
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java
index 827e12b4e7..d84384fd67 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java
@@ -172,7 +172,6 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
* positive.
*/
- @SuppressWarnings("ParameterName")
public void driveCartesian(double ySpeed, double xSpeed, double zRotation) {
driveCartesian(ySpeed, xSpeed, zRotation, 0.0);
}
@@ -190,7 +189,6 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
* @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use this
* to implement field-oriented controls.
*/
- @SuppressWarnings("ParameterName")
public void driveCartesian(double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
if (!m_reported) {
HAL.report(
@@ -221,7 +219,6 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
* positive.
*/
- @SuppressWarnings("ParameterName")
public void drivePolar(double magnitude, double angle, double zRotation) {
if (!m_reported) {
HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_KilloughPolar, 3);
@@ -247,7 +244,6 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
* positive.
* @return Wheel speeds [-1.0..1.0].
*/
- @SuppressWarnings("ParameterName")
public WheelSpeeds driveCartesianIK(double ySpeed, double xSpeed, double zRotation) {
return driveCartesianIK(ySpeed, xSpeed, zRotation, 0.0);
}
@@ -266,7 +262,6 @@ public class KilloughDrive extends RobotDriveBase implements Sendable, AutoClose
* to implement field-oriented controls.
* @return Wheel speeds [-1.0..1.0].
*/
- @SuppressWarnings("ParameterName")
public WheelSpeeds driveCartesianIK(
double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
ySpeed = MathUtil.clamp(ySpeed, -1.0, 1.0);
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 b1f57743c0..4888f84e98 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
@@ -139,7 +139,6 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
* positive.
*/
- @SuppressWarnings("ParameterName")
public void driveCartesian(double ySpeed, double xSpeed, double zRotation) {
driveCartesian(ySpeed, xSpeed, zRotation, 0.0);
}
@@ -157,7 +156,6 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea
* @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use this
* to implement field-oriented controls.
*/
- @SuppressWarnings("ParameterName")
public void driveCartesian(double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
if (!m_reported) {
HAL.report(
@@ -189,7 +187,6 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea
* @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
* positive.
*/
- @SuppressWarnings("ParameterName")
public void drivePolar(double magnitude, double angle, double zRotation) {
if (!m_reported) {
HAL.report(tResourceType.kResourceType_RobotDrive, tInstances.kRobotDrive2_MecanumPolar, 4);
@@ -215,7 +212,6 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea
* positive.
* @return Wheel speeds [-1.0..1.0].
*/
- @SuppressWarnings("ParameterName")
public static WheelSpeeds driveCartesianIK(double ySpeed, double xSpeed, double zRotation) {
return driveCartesianIK(ySpeed, xSpeed, zRotation, 0.0);
}
@@ -234,7 +230,6 @@ public class MecanumDrive extends RobotDriveBase implements Sendable, AutoClosea
* to implement field-oriented controls.
* @return Wheel speeds [-1.0..1.0].
*/
- @SuppressWarnings("ParameterName")
public static WheelSpeeds driveCartesianIK(
double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
ySpeed = MathUtil.clamp(ySpeed, -1.0, 1.0);
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java
index 728cc833ea..79f37333d8 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java
@@ -5,11 +5,9 @@
package edu.wpi.first.wpilibj.drive;
/** This is a 2D vector struct that supports basic vector operations. */
+@SuppressWarnings("MemberName")
public class Vector2d {
- @SuppressWarnings("MemberName")
public double x;
-
- @SuppressWarnings("MemberName")
public double y;
public Vector2d() {}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
index f24840fb2c..8651815b88 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
@@ -37,7 +37,6 @@ public final class SendableCameraWrapper implements Sendable, AutoCloseable {
}
/** Clears all cached wrapper objects. This should only be used in tests. */
- @SuppressWarnings("PMD.DefaultPackage")
static void clearWrappers() {
m_wrappers.clear();
}
@@ -73,7 +72,6 @@ public final class SendableCameraWrapper implements Sendable, AutoCloseable {
* @return a sendable wrapper object for the video source, usable in Shuffleboard via {@link
* ShuffleboardTab#add(Sendable)} and {@link ShuffleboardLayout#add(Sendable)}
*/
- @SuppressWarnings("PMD.CyclomaticComplexity")
public static SendableCameraWrapper wrap(String cameraName, String... cameraUrls) {
if (m_wrappers.containsKey(cameraName)) {
return m_wrappers.get(cameraName);
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
index 584a2ec671..f94fa35b9c 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16448_IMUSim.java
@@ -8,7 +8,7 @@ import edu.wpi.first.hal.SimDouble;
import edu.wpi.first.wpilibj.ADIS16448_IMU;
/** Class to control a simulated ADIS16448 gyroscope. */
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName"})
+@SuppressWarnings("TypeName")
public class ADIS16448_IMUSim {
private final SimDouble m_simGyroAngleX;
private final SimDouble m_simGyroAngleY;
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
index eb8ceb864e..57262440a6 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADIS16470_IMUSim.java
@@ -8,7 +8,7 @@ import edu.wpi.first.hal.SimDouble;
import edu.wpi.first.wpilibj.ADIS16470_IMU;
/** Class to control a simulated ADIS16470 gyroscope. */
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName"})
+@SuppressWarnings("TypeName")
public class ADIS16470_IMUSim {
private final SimDouble m_simGyroAngleX;
private final SimDouble m_simGyroAngleY;
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java
index 27e06a3cbd..0743cbde0b 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/ADXRS450_GyroSim.java
@@ -8,7 +8,7 @@ import edu.wpi.first.hal.SimDouble;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
/** Class to control a simulated ADXRS450 gyroscope. */
-@SuppressWarnings({"TypeName", "AbbreviationAsWordInName"})
+@SuppressWarnings("TypeName")
public class ADXRS450_GyroSim {
private final SimDouble m_simAngle;
private final SimDouble m_simRate;
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java
index 5714a2d94b..8aba25aabe 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/BuiltInAccelerometerSim.java
@@ -116,7 +116,6 @@ public class BuiltInAccelerometerSim {
*
* @param x the new reading of the X axis
*/
- @SuppressWarnings("ParameterName")
public void setX(double x) {
AccelerometerDataJNI.setX(m_index, x);
}
@@ -148,7 +147,6 @@ public class BuiltInAccelerometerSim {
*
* @param y the new reading of the Y axis
*/
- @SuppressWarnings("ParameterName")
public void setY(double y) {
AccelerometerDataJNI.setY(m_index, y);
}
@@ -180,7 +178,6 @@ public class BuiltInAccelerometerSim {
*
* @param z the new reading of the Z axis
*/
- @SuppressWarnings("ParameterName")
public void setZ(double z) {
AccelerometerDataJNI.setZ(m_index, z);
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java
index 005b68a0d0..3169a5db6a 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/CTREPCMSim.java
@@ -10,7 +10,6 @@ import edu.wpi.first.wpilibj.PneumaticsControlModule;
import edu.wpi.first.wpilibj.SensorUtil;
/** Class to control a simulated Pneumatic Control Module (PCM). */
-@SuppressWarnings("AbbreviationAsWordInName")
public class CTREPCMSim extends PneumaticsBaseSim {
/** Constructs for the default PCM. */
public CTREPCMSim() {
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
index 957075de3b..48c5a55b73 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DCMotorSim.java
@@ -59,7 +59,6 @@ public class DCMotorSim extends LinearSystemSim {
* @param jKgMetersSquared The moment of inertia of the DC motor. If this is unknown, use the
* {@link #DCMotorSim(LinearSystem, DCMotor, double, Matrix)} constructor.
*/
- @SuppressWarnings("ParameterName")
public DCMotorSim(DCMotor gearbox, double gearing, double jKgMetersSquared) {
super(LinearSystemId.createDCMotorSystem(gearbox, jKgMetersSquared, gearing));
m_gearbox = gearbox;
@@ -75,7 +74,6 @@ public class DCMotorSim extends LinearSystemSim {
* {@link #DCMotorSim(LinearSystem, DCMotor, double, Matrix)} constructor.
* @param measurementStdDevs The standard deviations of the measurements.
*/
- @SuppressWarnings("ParameterName")
public DCMotorSim(
DCMotor gearbox, double gearing, double jKgMetersSquared, Matrix measurementStdDevs) {
super(
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 0bdb76f63e..7a746a232e 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
@@ -44,13 +44,8 @@ public class DifferentialDrivetrainSim {
private double m_currentGearing;
private final double m_wheelRadiusMeters;
- @SuppressWarnings("MemberName")
private Matrix m_u;
-
- @SuppressWarnings("MemberName")
private Matrix m_x;
-
- @SuppressWarnings("MemberName")
private Matrix m_y;
private final double m_rb;
@@ -72,7 +67,6 @@ public class DifferentialDrivetrainSim {
* m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
* point.
*/
- @SuppressWarnings("ParameterName")
public DifferentialDrivetrainSim(
DCMotor driveMotor,
double gearing,
@@ -153,7 +147,6 @@ public class DifferentialDrivetrainSim {
*
* @param dtSeconds the time difference
*/
- @SuppressWarnings("LocalVariableName")
public void update(double dtSeconds) {
// Update state estimate with RK4
m_x = NumericalIntegration.rk4(this::getDynamics, m_x, m_u, dtSeconds);
@@ -316,7 +309,6 @@ public class DifferentialDrivetrainSim {
m_x.set(State.kRightPosition.value, 0, 0);
}
- @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.
@@ -373,10 +365,8 @@ public class DifferentialDrivetrainSim {
kLeftPosition(5),
kRightPosition(6);
- @SuppressWarnings("MemberName")
public final int value;
- @SuppressWarnings("ParameterName")
State(int i) {
this.value = i;
}
@@ -393,10 +383,8 @@ public class DifferentialDrivetrainSim {
k7p31(7.31),
k5p95(5.95);
- @SuppressWarnings("MemberName")
public final double value;
- @SuppressWarnings("ParameterName")
KitbotGearing(double i) {
this.value = i;
}
@@ -413,10 +401,8 @@ public class DifferentialDrivetrainSim {
kSingleNEOPerSide(DCMotor.getNEO(1)),
kDoubleNEOPerSide(DCMotor.getNEO(2));
- @SuppressWarnings("MemberName")
public final DCMotor value;
- @SuppressWarnings("ParameterName")
KitbotMotor(DCMotor i) {
this.value = i;
}
@@ -428,10 +414,8 @@ public class DifferentialDrivetrainSim {
kEightInch(Units.inchesToMeters(8)),
kTenInch(Units.inchesToMeters(10));
- @SuppressWarnings("MemberName")
public final double value;
- @SuppressWarnings("ParameterName")
KitbotWheelSize(double i) {
this.value = i;
}
@@ -479,7 +463,6 @@ public class DifferentialDrivetrainSim {
* point.
* @return A sim for the standard FRC kitbot.
*/
- @SuppressWarnings("ParameterName")
public static DifferentialDrivetrainSim createKitbotSim(
KitbotMotor motor,
KitbotGearing gearing,
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
index f6da659f25..aa0bf84d66 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/DriverStationSim.java
@@ -138,7 +138,6 @@ public final class DriverStationSim {
*
* @param eStop true to activate
*/
- @SuppressWarnings("ParameterName")
public static void setEStop(boolean eStop) {
DriverStationDataJNI.setEStop(eStop);
}
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 f4b2b607a0..025260a691 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
@@ -244,14 +244,13 @@ public class ElevatorSim extends LinearSystemSim {
* @param u The system inputs (voltage).
* @param dtSeconds The time difference between controller updates.
*/
- @SuppressWarnings({"ParameterName", "LambdaParameterName"})
@Override
protected Matrix updateX(Matrix currentXhat, Matrix u, double dtSeconds) {
// Calculate updated x-hat from Runge-Kutta.
var updatedXhat =
NumericalIntegration.rkdp(
- (x, u_) -> {
- Matrix xdot = m_plant.getA().times(x).plus(m_plant.getB().times(u_));
+ (x, _u) -> {
+ Matrix xdot = m_plant.getA().times(x).plus(m_plant.getB().times(_u));
if (m_simulateGravity) {
xdot = xdot.plus(VecBuilder.fill(0, -9.8));
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
index aaf13de0e4..90f911d246 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/FlywheelSim.java
@@ -58,7 +58,6 @@ public class FlywheelSim extends LinearSystemSim {
* @param jKgMetersSquared The moment of inertia of the flywheel. If this is unknown, use the
* {@link #FlywheelSim(LinearSystem, DCMotor, double, Matrix)} constructor.
*/
- @SuppressWarnings("ParameterName")
public FlywheelSim(DCMotor gearbox, double gearing, double jKgMetersSquared) {
super(LinearSystemId.createFlywheelSystem(gearbox, jKgMetersSquared, gearing));
m_gearbox = gearbox;
@@ -74,7 +73,6 @@ public class FlywheelSim extends LinearSystemSim {
* {@link #FlywheelSim(LinearSystem, DCMotor, double, Matrix)} constructor.
* @param measurementStdDevs The standard deviations of the measurements.
*/
- @SuppressWarnings("ParameterName")
public FlywheelSim(
DCMotor gearbox, double gearing, double jKgMetersSquared, Matrix measurementStdDevs) {
super(
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
index e6ffbca056..73b1170eab 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/LinearSystemSim.java
@@ -27,19 +27,13 @@ import org.ejml.simple.SimpleMatrix;
* @param The number of inputs to the system.
* @param The number of outputs of the system.
*/
-@SuppressWarnings("ClassTypeParameterName")
public class LinearSystemSim {
// The plant that represents the linear system.
protected final LinearSystem m_plant;
// Variables for state, output, and input.
- @SuppressWarnings("MemberName")
protected Matrix m_x;
-
- @SuppressWarnings("MemberName")
protected Matrix m_y;
-
- @SuppressWarnings("MemberName")
protected Matrix m_u;
// The standard deviations of measurements, used for adding noise
@@ -77,7 +71,6 @@ public class LinearSystemSim u) {
this.m_u = clampInput(u);
}
@@ -136,7 +128,6 @@ public class LinearSystemSim updateX(
Matrix currentXhat, Matrix u, double dtSeconds) {
return m_plant.calculateX(currentXhat, u, dtSeconds);
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java
index b170050ff9..055cecced2 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/REVPHSim.java
@@ -10,7 +10,6 @@ import edu.wpi.first.wpilibj.PneumaticHub;
import edu.wpi.first.wpilibj.SensorUtil;
/** Class to control a simulated PneumaticHub (PH). */
-@SuppressWarnings("AbbreviationAsWordInName")
public class REVPHSim extends PneumaticsBaseSim {
/** Constructs for the default PH. */
public REVPHSim() {
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java
index 976ba4aad2..fc341dc90f 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/RoboRioSim.java
@@ -21,7 +21,6 @@ public final class RoboRioSim {
* @return the {@link CallbackStore} object associated with this callback. Save a reference to
* this object so GC doesn't cancel the callback.
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static CallbackStore registerFPGAButtonCallback(
NotifyCallback callback, boolean initialNotify) {
int uid = RoboRioDataJNI.registerFPGAButtonCallback(callback, initialNotify);
@@ -33,7 +32,6 @@ public final class RoboRioSim {
*
* @return the FPGA button state
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static boolean getFPGAButton() {
return RoboRioDataJNI.getFPGAButton();
}
@@ -43,7 +41,6 @@ public final class RoboRioSim {
*
* @param fpgaButton the new state
*/
- @SuppressWarnings("AbbreviationAsWordInName")
public static void setFPGAButton(boolean fpgaButton) {
RoboRioDataJNI.setFPGAButton(fpgaButton);
}
@@ -76,7 +73,6 @@ public final class RoboRioSim {
*
* @param vInVoltage the new voltage
*/
- @SuppressWarnings("ParameterName")
public static void setVInVoltage(double vInVoltage) {
RoboRioDataJNI.setVInVoltage(vInVoltage);
}
@@ -109,7 +105,6 @@ public final class RoboRioSim {
*
* @param vInCurrent the new current
*/
- @SuppressWarnings("ParameterName")
public static void setVInCurrent(double vInCurrent) {
RoboRioDataJNI.setVInCurrent(vInCurrent);
}
@@ -526,7 +521,6 @@ public final class RoboRioSim {
*
* @param vInVoltage the new voltage
*/
- @SuppressWarnings("ParameterName")
public static void setBrownoutVoltage(double vInVoltage) {
RoboRioDataJNI.setBrownoutVoltage(vInVoltage);
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java
index da1213a3b2..24e3cca4ee 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/simulation/SPIAccelerometerSim.java
@@ -109,7 +109,6 @@ public class SPIAccelerometerSim {
*
* @param x the new reading of the X axis
*/
- @SuppressWarnings("ParameterName")
public void setX(double x) {
SPIAccelerometerDataJNI.setX(m_index, x);
}
@@ -141,7 +140,6 @@ public class SPIAccelerometerSim {
*
* @param y the new reading of the Y axis
*/
- @SuppressWarnings("ParameterName")
public void setY(double y) {
SPIAccelerometerDataJNI.setY(m_index, y);
}
@@ -173,7 +171,6 @@ public class SPIAccelerometerSim {
*
* @param z the new reading of the Z axis
*/
- @SuppressWarnings("ParameterName")
public void setZ(double z) {
SPIAccelerometerDataJNI.setZ(m_index, z);
}
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 87981f71dd..c64a434da4 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
@@ -22,7 +22,6 @@ public class SingleJointedArmSim extends LinearSystemSim {
private final double m_gearing;
// The length of the arm.
- @SuppressWarnings("MemberName")
private final double m_r;
// The minimum angle that the arm is capable of.
@@ -115,7 +114,6 @@ public class SingleJointedArmSim extends LinearSystemSim {
* @param armMassKg The mass of the arm.
* @param simulateGravity Whether gravity should be simulated or not.
*/
- @SuppressWarnings("ParameterName")
public SingleJointedArmSim(
DCMotor gearbox,
double gearing,
@@ -150,7 +148,6 @@ public class SingleJointedArmSim extends LinearSystemSim {
* @param simulateGravity Whether gravity should be simulated or not.
* @param measurementStdDevs The standard deviations of the measurements.
*/
- @SuppressWarnings("ParameterName")
public SingleJointedArmSim(
DCMotor gearbox,
double gearing,
@@ -270,7 +267,6 @@ public class SingleJointedArmSim extends LinearSystemSim {
* @param dtSeconds The time difference between controller updates.
*/
@Override
- @SuppressWarnings({"ParameterName", "LambdaParameterName"})
protected Matrix updateX(Matrix currentXhat, Matrix u, double dtSeconds) {
// Horizontal case:
// Torque = F * r = I * alpha
@@ -283,8 +279,8 @@ public class SingleJointedArmSim extends LinearSystemSim {
// cos(theta)]]
Matrix updatedXhat =
NumericalIntegration.rkdp(
- (Matrix x, Matrix u_) -> {
- Matrix xdot = m_plant.getA().times(x).plus(m_plant.getB().times(u_));
+ (Matrix x, Matrix _u) -> {
+ Matrix xdot = m_plant.getA().times(x).plus(m_plant.getB().times(_u));
if (m_simulateGravity) {
xdot =
xdot.plus(
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 b76f0560fb..4ae8c57a07 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
@@ -54,7 +54,6 @@ public class Field2d implements NTSendable {
* @param yMeters Y location, in meters
* @param rotation rotation
*/
- @SuppressWarnings("ParameterName")
public synchronized void setRobotPose(double xMeters, double yMeters, Rotation2d rotation) {
m_objects.get(0).setPose(xMeters, yMeters, rotation);
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
index d6c7a5e429..8b24430c7e 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/FieldObject2d.java
@@ -41,7 +41,6 @@ public class FieldObject2d {
* @param yMeters Y location, in meters
* @param rotation rotation
*/
- @SuppressWarnings("ParameterName")
public synchronized void setPose(double xMeters, double yMeters, Rotation2d rotation) {
setPose(new Pose2d(xMeters, yMeters, rotation));
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java
index a281b35d5b..4dbba041bf 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/Color.java
@@ -50,7 +50,6 @@ public class Color {
* @param v The v value [0-255]
* @return The color
*/
- @SuppressWarnings("ParameterName")
public static Color fromHSV(int h, int s, int v) {
if (s == 0) {
return new Color(v / 255.0, v / 255.0, v / 255.0);
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java
index 031d411bdb..6f00ba83a7 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/AddressableLEDBufferTest.java
@@ -19,7 +19,6 @@ import org.junit.jupiter.params.provider.MethodSource;
class AddressableLEDBufferTest {
@ParameterizedTest
@MethodSource("hsvToRgbProvider")
- @SuppressWarnings("ParameterName")
void hsvConvertTest(int h, int s, int v, int r, int g, int b) {
var buffer = new AddressableLEDBuffer(1);
buffer.setHSV(0, h, s, v);
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java
index c1ebd51f21..31277a3ba2 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/PS4ControllerTest.java
@@ -18,7 +18,6 @@ import org.junit.jupiter.params.provider.EnumSource;
class PS4ControllerTest {
@ParameterizedTest
@EnumSource(value = PS4Controller.Button.class)
- @SuppressWarnings({"VariableDeclarationUsageDistance"})
void testButtons(PS4Controller.Button button)
throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
HAL.initialize(500, 0);
@@ -32,10 +31,10 @@ class PS4ControllerTest {
String joyPressedMethodName = "get" + buttonName + "Pressed";
String joyReleasedMethodName = "get" + buttonName + "Released";
- Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
- Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
- Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
- Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
+ final Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
+ final Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
+ final Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
+ final Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
simSetMethod.invoke(joysim, false);
joysim.notifyNewData();
@@ -59,7 +58,6 @@ class PS4ControllerTest {
@ParameterizedTest
@EnumSource(value = PS4Controller.Axis.class)
- @SuppressWarnings({"VariableDeclarationUsageDistance"})
void testAxes(PS4Controller.Axis axis)
throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
HAL.initialize(500, 0);
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java
index af9c902fe2..b724bf4e63 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/XboxControllerTest.java
@@ -18,7 +18,6 @@ import org.junit.jupiter.params.provider.EnumSource;
class XboxControllerTest {
@ParameterizedTest
@EnumSource(value = XboxController.Button.class)
- @SuppressWarnings({"VariableDeclarationUsageDistance"})
void testButtons(XboxController.Button button)
throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
HAL.initialize(500, 0);
@@ -32,10 +31,10 @@ class XboxControllerTest {
String joyPressedMethodName = "get" + buttonName + "Pressed";
String joyReleasedMethodName = "get" + buttonName + "Released";
- Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
- Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
- Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
- Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
+ final Method simSetMethod = joysim.getClass().getMethod(simSetMethodName, boolean.class);
+ final Method joyGetMethod = joy.getClass().getMethod(joyGetMethodName);
+ final Method joyPressedMethod = joy.getClass().getMethod(joyPressedMethodName);
+ final Method joyReleasedMethod = joy.getClass().getMethod(joyReleasedMethodName);
simSetMethod.invoke(joysim, false);
joysim.notifyNewData();
@@ -59,7 +58,6 @@ class XboxControllerTest {
@ParameterizedTest
@EnumSource(value = XboxController.Axis.class)
- @SuppressWarnings({"VariableDeclarationUsageDistance"})
void testAxes(XboxController.Axis axis)
throws NoSuchMethodException, InvocationTargetException, IllegalAccessException {
HAL.initialize(500, 0);
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java
index ee747bc3c0..f58f7c741a 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/CTREPCMSimTest.java
@@ -18,7 +18,6 @@ import edu.wpi.first.wpilibj.simulation.testutils.BooleanCallback;
import edu.wpi.first.wpilibj.simulation.testutils.DoubleCallback;
import org.junit.jupiter.api.Test;
-@SuppressWarnings("AbbreviationAsWordInName")
class CTREPCMSimTest {
@Test
void testInitialization() {
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 47c1f666ca..fd2e7bab2e 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
@@ -19,7 +19,6 @@ import org.junit.jupiter.api.Test;
class ElevatorSimTest {
@Test
- @SuppressWarnings({"LocalVariableName", "resource"})
void testStateSpaceSimWithElevator() {
RoboRioSim.resetData();
diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java
index a4368313b8..c3c790181b 100644
--- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java
+++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/simulation/REVPHSimTest.java
@@ -19,7 +19,6 @@ import edu.wpi.first.wpilibj.simulation.testutils.DoubleCallback;
import edu.wpi.first.wpilibj.simulation.testutils.EnumCallback;
import org.junit.jupiter.api.Test;
-@SuppressWarnings("AbbreviationAsWordInName")
class REVPHSimTest {
@Test
void testInitialization() {
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
index 07b4881e82..43b84045aa 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdrivebot/Drivetrain.java
@@ -98,7 +98,6 @@ public class Drivetrain {
* @param xSpeed Linear velocity in m/s.
* @param rot Angular velocity in rad/s.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double rot) {
var wheelSpeeds = m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0.0, rot));
setSpeeds(wheelSpeeds);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
index 3b5d9e2f12..34014bc561 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java
@@ -108,7 +108,6 @@ public class Drivetrain {
* @param xSpeed Linear velocity in m/s.
* @param rot Angular velocity in rad/s.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double rot) {
var wheelSpeeds = m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0.0, rot));
setSpeeds(wheelSpeeds);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java
index a12a6fd20c..bb99244248 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleencoder/Robot.java
@@ -8,7 +8,6 @@ import edu.wpi.first.wpilibj.DutyCycleEncoder;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
-@SuppressWarnings("PMD.SingularField")
public class Robot extends TimedRobot {
private DutyCycleEncoder m_dutyCycleEncoder;
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java
index 584fbc6edb..c7350b089b 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/dutycycleinput/Robot.java
@@ -9,15 +9,12 @@ import edu.wpi.first.wpilibj.DutyCycle;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
-@SuppressWarnings("PMD.SingularField")
public class Robot extends TimedRobot {
- private DigitalInput m_input;
private DutyCycle m_dutyCycle;
@Override
public void robotInit() {
- m_input = new DigitalInput(0);
- m_dutyCycle = new DutyCycle(m_input);
+ m_dutyCycle = new DutyCycle(new DigitalInput(0));
}
@Override
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
index 9210265673..e6f2c18fbd 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
@@ -114,7 +114,6 @@ public class Drivetrain {
* @param rot Angular rate of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
var mecanumDriveWheelSpeeds =
m_kinematics.toWheelSpeeds(
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
index 7874d82c53..764f6b6546 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
@@ -113,7 +113,6 @@ public class DriveSubsystem extends SubsystemBase {
* @param rot Angular rate of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
if (fieldRelative) {
m_drive.driveCartesian(ySpeed, xSpeed, rot, -m_gyro.getAngle());
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
index 427284f918..e90d9463a7 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
@@ -126,7 +126,6 @@ public class Drivetrain {
* @param rot Angular rate of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
var mecanumDriveWheelSpeeds =
m_kinematics.toWheelSpeeds(
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java
index e119080207..19ddefd044 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Drivetrain.java
@@ -99,7 +99,6 @@ public class Drivetrain {
* @param xSpeed Linear velocity in m/s.
* @param rot Angular velocity in rad/s.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double rot) {
var wheelSpeeds = m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0.0, rot));
setSpeeds(wheelSpeeds);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
index 986875a4af..9ab81a3f24 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
@@ -113,7 +113,6 @@ public class Drivetrain {
* @param xSpeed the speed for the x axis
* @param rot the rotation
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double rot) {
setSpeeds(m_kinematics.toWheelSpeeds(new ChassisSpeeds(xSpeed, 0, rot)));
}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
index 99178d4e0d..a9691f58ba 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Robot.java
@@ -65,7 +65,6 @@ public class Robot extends TimedRobot {
}
@Override
- @SuppressWarnings("LocalVariableName")
public void teleopPeriodic() {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
index 3b71a0c644..0df6096cba 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
@@ -46,7 +46,6 @@ public class Drivetrain {
* @param rot Angular rate of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
var swerveModuleStates =
m_kinematics.toSwerveModuleStates(
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
index c0e364b972..0ec4d7ce8a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
@@ -99,7 +99,6 @@ public class DriveSubsystem extends SubsystemBase {
* @param rot Angular rate of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
var swerveModuleStates =
DriveConstants.kDriveKinematics.toSwerveModuleStates(
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
index e1d16a0182..c6231c210a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
@@ -58,7 +58,6 @@ public class Drivetrain {
* @param rot Angular rate of the robot.
* @param fieldRelative Whether the provided x and y speeds are relative to the field.
*/
- @SuppressWarnings("ParameterName")
public void drive(double xSpeed, double ySpeed, double rot, boolean fieldRelative) {
var swerveModuleStates =
m_kinematics.toSwerveModuleStates(
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
index dfd5b6c742..36bd2e8e1c 100644
--- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
@@ -22,7 +22,7 @@ public class MockDS {
data[5] = 0x00; // red 1 station
}
- @SuppressWarnings("MissingJavadocMethod")
+ /** Start the mock DS thread. */
public void start() {
m_thread =
new Thread(
@@ -67,7 +67,7 @@ public class MockDS {
m_thread.start();
}
- @SuppressWarnings("MissingJavadocMethod")
+ /** Stop the mock DS thread. */
public void stop() {
if (m_thread == null) {
return;
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
index 548c2e0fa7..f2bc522e38 100644
--- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
@@ -45,7 +45,12 @@ public class PDPTest extends AbstractComsSetup {
me = null;
}
- @SuppressWarnings("MissingJavadocMethod")
+ /**
+ * PDPTest constructor.
+ *
+ * @param mef Motor encoder fixture.
+ * @param expectedCurrentDraw Expected current draw in Amps.
+ */
public PDPTest(MotorEncoderFixture> mef, Double expectedCurrentDraw) {
logger.fine("Constructor with: " + mef.getType());
if (me != null && !me.equals(mef)) {
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
index c8afb4baa8..b5e0fc8fd9 100644
--- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
@@ -41,24 +41,32 @@ public class PIDTest extends AbstractComsSetup {
private PIDController m_controller = null;
private static MotorEncoderFixture> me = null;
- @SuppressWarnings({"MemberName", "EmptyLineSeparator", "MultipleVariableDeclarations"})
- private final Double k_p, k_i, k_d;
+ private final Double m_p;
+ private final Double m_i;
+ private final Double m_d;
@Override
protected Logger getClassLogger() {
return logger;
}
- @SuppressWarnings({"ParameterName", "MissingJavadocMethod"})
+ /**
+ * PIDTest constructor.
+ *
+ * @param p P gain.
+ * @param i I gain.
+ * @param d D gain.
+ * @param mef Motor encoder fixture.
+ */
public PIDTest(Double p, Double i, Double d, MotorEncoderFixture> mef) {
logger.fine("Constructor with: " + mef.getType());
if (PIDTest.me != null && !PIDTest.me.equals(mef)) {
PIDTest.me.teardown();
}
PIDTest.me = mef;
- this.k_p = p;
- this.k_i = i;
- this.k_d = d;
+ this.m_p = p;
+ this.m_i = i;
+ this.m_d = d;
}
@Parameters
@@ -97,7 +105,7 @@ public class PIDTest extends AbstractComsSetup {
m_table = NetworkTableInstance.getDefault().getTable("TEST_PID");
m_builder = new SendableBuilderImpl();
m_builder.setTable(m_table);
- m_controller = new PIDController(k_p, k_i, k_d);
+ m_controller = new PIDController(m_p, m_i, m_d);
m_controller.initSendable(m_builder);
}
@@ -128,9 +136,9 @@ public class PIDTest extends AbstractComsSetup {
m_controller.getPositionError(),
0);
m_builder.update();
- assertEquals(k_p, m_table.getEntry("Kp").getDouble(9999999), 0);
- assertEquals(k_i, m_table.getEntry("Ki").getDouble(9999999), 0);
- assertEquals(k_d, m_table.getEntry("Kd").getDouble(9999999), 0);
+ assertEquals(m_p, m_table.getEntry("Kp").getDouble(9999999), 0);
+ assertEquals(m_i, m_table.getEntry("Ki").getDouble(9999999), 0);
+ assertEquals(m_d, m_table.getEntry("Kd").getDouble(9999999), 0);
assertEquals(reference, m_table.getEntry("reference").getDouble(9999999), 0);
assertFalse(m_table.getEntry("enabled").getBoolean(true));
}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
index 220db183e3..42a53b3132 100644
--- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
@@ -152,7 +152,6 @@ public abstract class MotorEncoderFixture implements
* deallocated.
*/
@Override
- @SuppressWarnings("Regexp")
public void teardown() {
if (!m_tornDown) {
if (m_motor != null) {
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
index c41ff8a7e9..1e48c9ce7b 100644
--- a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
@@ -122,8 +122,7 @@ class FirstSubSuiteTest {
public static final String METHODNAME = "aTestMethod";
@Test
- @SuppressWarnings("MethodName")
- public void aTestMethod() {}
+ public void testMethod() {}
}
@SuppressWarnings("OneTopLevelClass")
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 6948097214..258d640af9 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
@@ -210,7 +210,7 @@ public final class TestBench {
return pairs;
}
- @SuppressWarnings("MissingJavadocMethod")
+ /** Returns the analog I/O cross-connect fixture. */
public static AnalogCrossConnectFixture getAnalogCrossConnectFixture() {
return new AnalogCrossConnectFixture() {
@Override
@@ -225,7 +225,7 @@ public final class TestBench {
};
}
- @SuppressWarnings("MissingJavadocMethod")
+ /** Returns the relay cross-connect fixture. */
public static RelayCrossConnectFixture getRelayCrossConnectFixture() {
return new RelayCrossConnectFixture() {
@Override
diff --git a/wpimath/src/generate/Nat.java.jinja b/wpimath/src/generate/Nat.java.jinja
index 31451d2612..cbc0ddb24e 100644
--- a/wpimath/src/generate/Nat.java.jinja
+++ b/wpimath/src/generate/Nat.java.jinja
@@ -16,7 +16,6 @@ import edu.wpi.first.math.numbers.N{{ num }};
*
* @param The {@link Num} this represents.
*/
-@SuppressWarnings({"MethodName", "unused"})
public interface Nat {
/**
* The number this interface represents.
diff --git a/wpimath/src/main/java/edu/wpi/first/math/Drake.java b/wpimath/src/main/java/edu/wpi/first/math/Drake.java
index 766f7e9c79..b1a5f95aeb 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/Drake.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/Drake.java
@@ -18,7 +18,6 @@ public final class Drake {
* @param R Input cost matrix.
* @return Solution of DARE.
*/
- @SuppressWarnings({"LocalVariableName", "ParameterName"})
public static SimpleMatrix discreteAlgebraicRiccatiEquation(
SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R) {
var S = new SimpleMatrix(A.numRows(), A.numCols());
@@ -44,7 +43,6 @@ public final class Drake {
* @param R Input cost matrix.
* @return Solution of DARE.
*/
- @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public static
Matrix discreteAlgebraicRiccatiEquation(
Matrix A,
@@ -66,7 +64,6 @@ public final class Drake {
* @param N State-input cross-term cost matrix.
* @return Solution of DARE.
*/
- @SuppressWarnings({"LocalVariableName", "ParameterName"})
public static SimpleMatrix discreteAlgebraicRiccatiEquation(
SimpleMatrix A, SimpleMatrix B, SimpleMatrix Q, SimpleMatrix R, SimpleMatrix N) {
// See
@@ -99,7 +96,6 @@ public final class Drake {
* @param N State-input cross-term cost matrix.
* @return Solution of DARE.
*/
- @SuppressWarnings({"ParameterName", "MethodTypeParameterName"})
public static
Matrix discreteAlgebraicRiccatiEquation(
Matrix A,
diff --git a/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java b/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java
index e5b195224c..2ee010f194 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/MatBuilder.java
@@ -24,7 +24,6 @@ public class MatBuilder {
* @param data The data to fill the matrix with.
* @return The constructed matrix.
*/
- @SuppressWarnings("LineLength")
public final Matrix fill(double... data) {
if (Objects.requireNonNull(data).length != this.m_rows.getNum() * this.m_cols.getNum()) {
throw new IllegalArgumentException(
diff --git a/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java b/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
index a299ae359e..95ed5bfe25 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/MathUtil.java
@@ -142,7 +142,6 @@ public final class MathUtil {
* @param t How far between the two values to interpolate. This is clamped to [0, 1].
* @return The interpolated value.
*/
- @SuppressWarnings("ParameterName")
public static double interpolate(double startValue, double endValue, double t) {
return startValue + (endValue - startValue) * MathUtil.clamp(t, 0, 1);
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/Matrix.java b/wpimath/src/main/java/edu/wpi/first/math/Matrix.java
index 0676784d72..18c20a9e0f 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/Matrix.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/Matrix.java
@@ -331,7 +331,6 @@ public class Matrix {
* @param b The right-hand side of the equation to solve.
* @return The solution to the linear system.
*/
- @SuppressWarnings("ParameterName")
public final Matrix solve(Matrix b) {
return new Matrix<>(this.m_storage.solve(Objects.requireNonNull(b).m_storage));
}
@@ -464,7 +463,6 @@ public class Matrix {
* @param b Scalar.
* @return The element by element power of "this" and b.
*/
- @SuppressWarnings("ParameterName")
public final Matrix elementPower(double b) {
return new Matrix<>(this.m_storage.elementPower(b));
}
@@ -477,7 +475,6 @@ public class Matrix {
* @param b Scalar.
* @return The element by element power of "this" and b.
*/
- @SuppressWarnings("ParameterName")
public final Matrix elementPower(int b) {
return new Matrix<>(this.m_storage.elementPower((double) b));
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/Pair.java b/wpimath/src/main/java/edu/wpi/first/math/Pair.java
index d1a68c7099..8ddf1ae37b 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/Pair.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/Pair.java
@@ -21,7 +21,6 @@ public class Pair {
return m_second;
}
- @SuppressWarnings("ParameterName")
public static Pair of(A a, B b) {
return new Pair<>(a, b);
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java b/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java
index fc78dd1c0a..1ae983e268 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/SimpleMatrixUtils.java
@@ -21,36 +21,34 @@ public final class SimpleMatrixUtils {
* @param matrix The matrix to compute the exponential of.
* @return The resultant matrix.
*/
- @SuppressWarnings({"LocalVariableName", "LineLength"})
public static SimpleMatrix expm(SimpleMatrix matrix) {
BiFunction solveProvider = SimpleBase::solve;
SimpleMatrix A = matrix;
double A_L1 = NormOps_DDRM.inducedP1(matrix.getDDRM());
- int n_squarings = 0;
+ int nSquarings = 0;
if (A_L1 < 1.495585217958292e-002) {
- Pair pair = _pade3(A);
- return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+ Pair pair = pade3(A);
+ return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else if (A_L1 < 2.539398330063230e-001) {
- Pair pair = _pade5(A);
- return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+ Pair pair = pade5(A);
+ return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else if (A_L1 < 9.504178996162932e-001) {
- Pair pair = _pade7(A);
- return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+ Pair pair = pade7(A);
+ return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else if (A_L1 < 2.097847961257068e+000) {
- Pair pair = _pade9(A);
- return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+ Pair pair = pade9(A);
+ return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
} else {
double maxNorm = 5.371920351148152;
double log = Math.log(A_L1 / maxNorm) / Math.log(2); // logb(2, arg)
- n_squarings = (int) Math.max(0, Math.ceil(log));
- A = A.divide(Math.pow(2.0, n_squarings));
- Pair pair = _pade13(A);
- return dispatchPade(pair.getFirst(), pair.getSecond(), n_squarings, solveProvider);
+ nSquarings = (int) Math.max(0, Math.ceil(log));
+ A = A.divide(Math.pow(2.0, nSquarings));
+ Pair pair = pade13(A);
+ return dispatchPade(pair.getFirst(), pair.getSecond(), nSquarings, solveProvider);
}
}
- @SuppressWarnings({"LocalVariableName", "ParameterName", "LineLength"})
private static SimpleMatrix dispatchPade(
SimpleMatrix U,
SimpleMatrix V,
@@ -68,8 +66,7 @@ public final class SimpleMatrixUtils {
return R;
}
- @SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName"})
- private static Pair _pade3(SimpleMatrix A) {
+ private static Pair pade3(SimpleMatrix A) {
double[] b = new double[] {120, 60, 12, 1};
SimpleMatrix ident = eye(A.numRows(), A.numCols());
@@ -79,8 +76,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
- @SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName"})
- private static Pair _pade5(SimpleMatrix A) {
+ private static Pair pade5(SimpleMatrix A) {
double[] b = new double[] {30240, 15120, 3360, 420, 30, 1};
SimpleMatrix ident = eye(A.numRows(), A.numCols());
SimpleMatrix A2 = A.mult(A);
@@ -92,8 +88,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
- @SuppressWarnings({"MethodName", "LocalVariableName", "LineLength", "ParameterName"})
- private static Pair _pade7(SimpleMatrix A) {
+ private static Pair pade7(SimpleMatrix A) {
double[] b = new double[] {17297280, 8648640, 1995840, 277200, 25200, 1512, 56, 1};
SimpleMatrix ident = eye(A.numRows(), A.numCols());
SimpleMatrix A2 = A.mult(A);
@@ -108,8 +103,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
- @SuppressWarnings({"MethodName", "LocalVariableName", "ParameterName", "LineLength"})
- private static Pair _pade9(SimpleMatrix A) {
+ private static Pair pade9(SimpleMatrix A) {
double[] b =
new double[] {
17643225600.0, 8821612800.0, 2075673600, 302702400, 30270240, 2162160, 110880, 3960, 90, 1
@@ -137,8 +131,7 @@ public final class SimpleMatrixUtils {
return new Pair<>(U, V);
}
- @SuppressWarnings({"MethodName", "LocalVariableName", "LineLength", "ParameterName"})
- private static Pair _pade13(SimpleMatrix A) {
+ private static Pair pade13(SimpleMatrix A) {
double[] b =
new double[] {
64764752532480000.0,
@@ -245,7 +238,6 @@ public final class SimpleMatrixUtils {
* @param A the matrix to exponentiate.
* @return the exponential of A.
*/
- @SuppressWarnings("ParameterName")
public static SimpleMatrix exp(SimpleMatrix A) {
SimpleMatrix toReturn = new SimpleMatrix(A.numRows(), A.numRows());
WPIMathJNI.exp(A.getDDRM().getData(), A.numRows(), toReturn.getDDRM().getData());
diff --git a/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java b/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java
index 520eaa72fe..a04184523d 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/StateSpaceUtil.java
@@ -11,7 +11,6 @@ import edu.wpi.first.math.numbers.N4;
import java.util.Random;
import org.ejml.simple.SimpleMatrix;
-@SuppressWarnings("ParameterName")
public final class StateSpaceUtil {
private static Random rand = new Random();
@@ -31,7 +30,6 @@ public final class StateSpaceUtil {
* output measurement.
* @return Process noise or measurement noise covariance matrix.
*/
- @SuppressWarnings("MethodTypeParameterName")
public static Matrix makeCovarianceMatrix(
Nat states, Matrix stdDevs) {
var result = new Matrix<>(states, states);
@@ -71,7 +69,6 @@ public final class StateSpaceUtil {
* excursions of the control inputs from no actuation.
* @return State excursion or control effort cost matrix.
*/
- @SuppressWarnings("MethodTypeParameterName")
public static Matrix makeCostMatrix(
Matrix tolerances) {
Matrix result =
@@ -102,7 +99,6 @@ public final class StateSpaceUtil {
* @param B Input matrix.
* @return If the system is stabilizable.
*/
- @SuppressWarnings("MethodTypeParameterName")
public static boolean isStabilizable(
Matrix A, Matrix B) {
return WPIMathJNI.isStabilizable(A.getNumRows(), B.getNumCols(), A.getData(), B.getData());
@@ -121,7 +117,6 @@ public final class StateSpaceUtil {
* @param C Output matrix.
* @return If the system is detectable.
*/
- @SuppressWarnings("MethodTypeParameterName")
public static boolean isDetectable(
Matrix A, Matrix C) {
return WPIMathJNI.isStabilizable(
@@ -147,7 +142,6 @@ public final class StateSpaceUtil {
* @param The number of inputs.
* @return The clamped input.
*/
- @SuppressWarnings({"ParameterName", "LocalVariableName"})
public static Matrix clampInputMaxMagnitude(
Matrix u, Matrix umin, Matrix umax) {
var result = new Matrix(new SimpleMatrix(u.getNumRows(), 1));
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
index 83a60e31ce..c98f46c8ad 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ArmFeedforward.java
@@ -8,7 +8,6 @@ package edu.wpi.first.math.controller;
* A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting
* against the force of gravity on a beam suspended at an angle).
*/
-@SuppressWarnings("MemberName")
public class ArmFeedforward {
public final double ks;
public final double kcos;
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 d4beabdc36..385c5c0342 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
@@ -29,16 +29,13 @@ import java.util.function.Function;
* For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
-@SuppressWarnings({"ParameterName", "LocalVariableName", "MemberName", "ClassTypeParameterName"})
public class ControlAffinePlantInversionFeedforward {
/** The current reference state. */
- @SuppressWarnings("MemberName")
private Matrix m_r;
/** The computed feedforward. */
private Matrix m_uff;
- @SuppressWarnings("MemberName")
private final Matrix m_B;
private final Nat m_inputs;
@@ -181,7 +178,6 @@ public class ControlAffinePlantInversionFeedforward calculate(Matrix r, Matrix nextR) {
var rDot = (nextR.minus(r)).div(m_dt);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiter.java b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiter.java
index 7a0ff5e69d..81eb231295 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveAccelerationLimiter.java
@@ -50,7 +50,6 @@ public class DifferentialDriveAccelerationLimiter {
* @param rightVoltage The unconstrained right motor voltage.
* @return The constrained wheel voltages.
*/
- @SuppressWarnings("LocalVariableName")
public DifferentialDriveWheelVoltages calculate(
double leftVelocity, double rightVelocity, double leftVoltage, double rightVoltage) {
var u = new MatBuilder<>(Nat.N2(), Nat.N1()).fill(leftVoltage, rightVoltage);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java
index 55f12b9f6d..2fbd0aa381 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/DifferentialDriveWheelVoltages.java
@@ -5,7 +5,6 @@
package edu.wpi.first.math.controller;
/** Motor voltages for a differential drive. */
-@SuppressWarnings("MemberName")
public class DifferentialDriveWheelVoltages {
public double left;
public double right;
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
index 248015f134..9f4dd863ff 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ElevatorFeedforward.java
@@ -8,7 +8,6 @@ package edu.wpi.first.math.controller;
* A helper class that computes feedforward outputs for a simple elevator (modeled as a motor acting
* against the force of gravity).
*/
-@SuppressWarnings("MemberName")
public class ElevatorFeedforward {
public final double ks;
public final double kg;
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
index be813cc437..b77c259e92 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/HolonomicDriveController.java
@@ -20,7 +20,6 @@ import edu.wpi.first.math.trajectory.Trajectory;
* are decoupled from translations, users can specify a custom heading that the drivetrain should
* point toward. This heading reference is profiled for smoothness.
*/
-@SuppressWarnings("MemberName")
public class HolonomicDriveController {
private Pose2d m_poseError = new Pose2d();
private Rotation2d m_rotationError = new Rotation2d();
@@ -40,7 +39,6 @@ public class HolonomicDriveController {
* @param yController A PID Controller to respond to error in the field-relative y direction.
* @param thetaController A profiled PID controller to respond to error in angle.
*/
- @SuppressWarnings("ParameterName")
public HolonomicDriveController(
PIDController xController, PIDController yController, ProfiledPIDController thetaController) {
m_xController = xController;
@@ -81,7 +79,6 @@ public class HolonomicDriveController {
* @param angleRef The angular reference.
* @return The next output of the holonomic drive controller.
*/
- @SuppressWarnings("LocalVariableName")
public ChassisSpeeds calculate(
Pose2d currentPose, Pose2d poseRef, double linearVelocityRefMeters, Rotation2d angleRef) {
// If this is the first run, then we need to reset the theta controller to the current pose's
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 6d620014a5..7aa4cfa913 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
@@ -20,18 +20,14 @@ import org.ejml.simple.SimpleMatrix;
* For more on the underlying math, read appendix B.3 in
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
-@SuppressWarnings("ClassTypeParameterName")
public class ImplicitModelFollower {
// Computed controller output
- @SuppressWarnings("MemberName")
private Matrix m_u;
// State space conversion gain
- @SuppressWarnings("MemberName")
private Matrix m_A;
// Input space conversion gain
- @SuppressWarnings("MemberName")
private Matrix m_B;
/**
@@ -53,7 +49,6 @@ public class ImplicitModelFollower A,
Matrix B,
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
index b31d146d81..46254a3b12 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVDifferentialDriveController.java
@@ -45,10 +45,8 @@ public class LTVDifferentialDriveController {
kLeftVelocity(3),
kRightVelocity(4);
- @SuppressWarnings("MemberName")
public final int value;
- @SuppressWarnings("ParameterName")
State(int i) {
this.value = i;
}
@@ -64,7 +62,6 @@ public class LTVDifferentialDriveController {
* @param relems The maximum desired control effort for each input.
* @param dt Discretization timestep in seconds.
*/
- @SuppressWarnings("LocalVariableName")
public LTVDifferentialDriveController(
LinearSystem plant,
double trackwidth,
@@ -188,7 +185,6 @@ public class LTVDifferentialDriveController {
* @param rightVelocityRef The desired right velocity in meters per second.
* @return Left and right output voltages of the LTV controller.
*/
- @SuppressWarnings("LocalVariableName")
public DifferentialDriveWheelVoltages calculate(
Pose2d currentPose,
double leftVelocity,
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
index 2f55be798d..701f21bbf4 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LTVUnicycleController.java
@@ -25,7 +25,6 @@ import edu.wpi.first.math.trajectory.Trajectory;
* See section 8.9 in Controls Engineering in FRC for a derivation of the control law we used
* shown in theorem 8.9.1.
*/
-@SuppressWarnings("MemberName")
public class LTVUnicycleController {
// LUT from drivetrain linear velocity to LQR gain
private final InterpolatingMatrixTreeMap m_table =
@@ -41,10 +40,8 @@ public class LTVUnicycleController {
kY(1),
kHeading(2);
- @SuppressWarnings("MemberName")
public final int value;
- @SuppressWarnings("ParameterName")
State(int i) {
this.value = i;
}
@@ -94,7 +91,6 @@ public class LTVUnicycleController {
* @param maxVelocity The maximum velocity in meters per second for the controller gain lookup
* table. The default is 9 m/s.
*/
- @SuppressWarnings("LocalVariableName")
public LTVUnicycleController(
Vector qelems, Vector relems, double dt, double maxVelocity) {
// The change in global pose for a unicycle is defined by the following
@@ -191,7 +187,6 @@ public class LTVUnicycleController {
m_poseError = poseRef.relativeTo(currentPose);
- @SuppressWarnings("LocalVariableName")
var K = m_table.get(linearVelocityRef);
var e =
new MatBuilder<>(Nat.N3(), Nat.N1())
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
index 627c27262d..a7628512af 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearPlantInversionFeedforward.java
@@ -20,20 +20,16 @@ import org.ejml.simple.SimpleMatrix;
* For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
-@SuppressWarnings({"ParameterName", "LocalVariableName", "MemberName", "ClassTypeParameterName"})
public class LinearPlantInversionFeedforward<
States extends Num, Inputs extends Num, Outputs extends Num> {
/** The current reference state. */
- @SuppressWarnings("MemberName")
private Matrix m_r;
/** The computed feedforward. */
private Matrix m_uff;
- @SuppressWarnings("MemberName")
private final Matrix m_B;
- @SuppressWarnings("MemberName")
private final Matrix m_A;
/**
@@ -54,7 +50,6 @@ public class LinearPlantInversionFeedforward<
* @param B Continuous input matrix of the plant being controlled.
* @param dtSeconds Discretization timestep.
*/
- @SuppressWarnings({"ParameterName", "LocalVariableName"})
public LinearPlantInversionFeedforward(
Matrix A, Matrix B, double dtSeconds) {
var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
@@ -143,7 +138,6 @@ public class LinearPlantInversionFeedforward<
* @param nextR The reference state of the future timestep (k + dt).
* @return The calculated feedforward.
*/
- @SuppressWarnings({"ParameterName", "LocalVariableName"})
public Matrix calculate(Matrix r, Matrix nextR) {
m_uff = new Matrix<>(m_B.solve(nextR.minus(m_A.times(r))));
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 190cd2a678..dce1748587 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
@@ -22,18 +22,14 @@ import org.ejml.simple.SimpleMatrix;
* For more on the underlying math, read
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf.
*/
-@SuppressWarnings("ClassTypeParameterName")
public class LinearQuadraticRegulator {
/** The current reference state. */
- @SuppressWarnings("MemberName")
private Matrix m_r;
/** The computed and capped controller output. */
- @SuppressWarnings("MemberName")
private Matrix m_u;
// Controller gain.
- @SuppressWarnings("MemberName")
private Matrix m_K;
/**
@@ -68,7 +64,6 @@ public class LinearQuadraticRegulator A,
Matrix B,
@@ -93,7 +88,6 @@ public class LinearQuadraticRegulator A,
Matrix B,
@@ -145,7 +139,6 @@ public class LinearQuadraticRegulator A,
Matrix B,
@@ -233,7 +226,6 @@ public class LinearQuadraticRegulator calculate(Matrix x) {
m_u = m_K.times(m_r.minus(x));
return m_u;
@@ -246,7 +238,6 @@ public class LinearQuadraticRegulator calculate(Matrix x, Matrix nextR) {
m_r = nextR;
return calculate(x);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java
index 3ebcbd877a..fd3587ebc5 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/ProfiledPIDController.java
@@ -33,7 +33,6 @@ public class ProfiledPIDController implements Sendable {
* @param Kd The derivative coefficient.
* @param constraints Velocity and acceleration constraints for goal.
*/
- @SuppressWarnings("ParameterName")
public ProfiledPIDController(
double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints) {
this(Kp, Ki, Kd, constraints, 0.02);
@@ -48,7 +47,6 @@ public class ProfiledPIDController implements Sendable {
* @param constraints Velocity and acceleration constraints for goal.
* @param period The period between controller updates in seconds. The default is 0.02 seconds.
*/
- @SuppressWarnings("ParameterName")
public ProfiledPIDController(
double Kp, double Ki, double Kd, TrapezoidProfile.Constraints constraints, double period) {
m_controller = new PIDController(Kp, Ki, Kd, period);
@@ -66,7 +64,6 @@ public class ProfiledPIDController implements Sendable {
* @param Ki Integral coefficient
* @param Kd Differential coefficient
*/
- @SuppressWarnings("ParameterName")
public void setPID(double Kp, double Ki, double Kd) {
m_controller.setPID(Kp, Ki, Kd);
}
@@ -76,7 +73,6 @@ public class ProfiledPIDController implements Sendable {
*
* @param Kp proportional coefficient
*/
- @SuppressWarnings("ParameterName")
public void setP(double Kp) {
m_controller.setP(Kp);
}
@@ -86,7 +82,6 @@ public class ProfiledPIDController implements Sendable {
*
* @param Ki integral coefficient
*/
- @SuppressWarnings("ParameterName")
public void setI(double Ki) {
m_controller.setI(Ki);
}
@@ -96,7 +91,6 @@ public class ProfiledPIDController implements Sendable {
*
* @param Kd differential coefficient
*/
- @SuppressWarnings("ParameterName")
public void setD(double Kd) {
m_controller.setD(Kd);
}
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java b/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java
index 7f35daeb65..5683987bc6 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/RamseteController.java
@@ -33,10 +33,8 @@ import edu.wpi.first.math.trajectory.Trajectory;
* derivation and analysis.
*/
public class RamseteController {
- @SuppressWarnings("MemberName")
private final double m_b;
- @SuppressWarnings("MemberName")
private final double m_zeta;
private Pose2d m_poseError = new Pose2d();
@@ -51,7 +49,6 @@ public class RamseteController {
* @param zeta Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger values provide
* more damping in response.
*/
- @SuppressWarnings("ParameterName")
public RamseteController(double b, double zeta) {
m_b = b;
m_zeta = zeta;
@@ -101,7 +98,6 @@ public class RamseteController {
* @param angularVelocityRefRadiansPerSecond The desired angular velocity in radians per second.
* @return The next controller output.
*/
- @SuppressWarnings("LocalVariableName")
public ChassisSpeeds calculate(
Pose2d currentPose,
Pose2d poseRef,
@@ -141,7 +137,6 @@ public class RamseteController {
* @param desiredState The desired pose, linear velocity, and angular velocity from a trajectory.
* @return The next controller output.
*/
- @SuppressWarnings("LocalVariableName")
public ChassisSpeeds calculate(Pose2d currentPose, Trajectory.State desiredState) {
return calculate(
currentPose,
@@ -164,7 +159,6 @@ public class RamseteController {
*
* @param x Value of which to take sinc(x).
*/
- @SuppressWarnings("ParameterName")
private static double sinc(double x) {
if (Math.abs(x) < 1e-9) {
return 1.0 - 1.0 / 6.0 * x * x;
diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java b/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
index a1e5f681cb..714d70527a 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/controller/SimpleMotorFeedforward.java
@@ -9,7 +9,6 @@ import edu.wpi.first.math.Nat;
import edu.wpi.first.math.system.plant.LinearSystemId;
/** A helper class that computes feedforward outputs for a simple permanent-magnet DC motor. */
-@SuppressWarnings("MemberName")
public class SimpleMotorFeedforward {
public final double ks;
public final double kv;
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java
index a6d8b448a7..0f91a1db83 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/AngleStatistics.java
@@ -87,7 +87,6 @@ public final class AngleStatistics {
* @param angleStateIdx The row containing the angles.
* @return Mean of sigma points.
*/
- @SuppressWarnings("checkstyle:ParameterName")
public static Matrix angleMean(
Matrix sigmas, Matrix, N1> Wm, int angleStateIdx) {
double[] angleSigmas = sigmas.extractRowVector(angleStateIdx).getData();
@@ -115,7 +114,6 @@ public final class AngleStatistics {
* @param angleStateIdx The row containing the angles.
* @return Function returning mean of sigma points.
*/
- @SuppressWarnings("LambdaParameterName")
public static BiFunction, Matrix, N1>, Matrix> angleMean(
int angleStateIdx) {
return (sigmas, Wm) -> angleMean(sigmas, Wm, angleStateIdx);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
index f7be897762..c5c05ca948 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/DifferentialDrivePoseEstimator.java
@@ -112,7 +112,6 @@ public class DifferentialDrivePoseEstimator {
* theta]ᵀ, with units in meters and radians.
* @param nominalDtSeconds The time in seconds between each robot loop.
*/
- @SuppressWarnings("ParameterName")
public DifferentialDrivePoseEstimator(
Rotation2d gyroAngle,
Pose2d initialPoseMeters,
@@ -172,7 +171,6 @@ public class DifferentialDrivePoseEstimator {
m_visionContR = StateSpaceUtil.makeCovarianceMatrix(Nat.N3(), visionMeasurementStdDevs);
}
- @SuppressWarnings({"ParameterName", "MethodName"})
private Matrix f(Matrix x, Matrix u) {
// Apply a rotation matrix. Note that we do *not* add x--Runge-Kutta does that for us.
var theta = x.get(2, 0);
@@ -343,7 +341,6 @@ public class DifferentialDrivePoseEstimator {
* last time you called {@link DifferentialDrivePoseEstimator#resetPosition}.
* @return The estimated pose of the robot in meters.
*/
- @SuppressWarnings({"LocalVariableName", "ParameterName"})
public Pose2d updateWithTime(
double currentTimeSeconds,
Rotation2d gyroAngle,
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
index 10d6a548f3..85adddc5eb 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java
@@ -34,16 +34,13 @@ import java.util.function.BiFunction;
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
*/
-@SuppressWarnings("ClassTypeParameterName")
public class ExtendedKalmanFilter
implements KalmanTypeFilter {
private final Nat m_states;
private final Nat m_outputs;
- @SuppressWarnings("MemberName")
private final BiFunction, Matrix, Matrix> m_f;
- @SuppressWarnings("MemberName")
private final BiFunction, Matrix, Matrix> m_h;
private BiFunction, Matrix, Matrix> m_residualFuncY;
@@ -53,10 +50,8 @@ public class ExtendedKalmanFilter m_initP;
private final Matrix m_contR;
- @SuppressWarnings("MemberName")
private Matrix m_xHat;
- @SuppressWarnings("MemberName")
private Matrix m_P;
private double m_dtSeconds;
@@ -73,7 +68,6 @@ public class ExtendedKalmanFilter states,
Nat inputs,
@@ -111,7 +105,6 @@ public class ExtendedKalmanFilter states,
Nat inputs,
@@ -219,7 +212,6 @@ public class ExtendedKalmanFilter xHat) {
m_xHat = xHat;
@@ -248,7 +240,6 @@ public class ExtendedKalmanFilter u, double dtSeconds) {
predict(u, m_f, dtSeconds);
@@ -261,7 +252,6 @@ public class ExtendedKalmanFilter u,
BiFunction, Matrix, Matrix> f,
@@ -288,7 +278,6 @@ public class ExtendedKalmanFilter u, Matrix y) {
correct(m_outputs, u, y, m_h, m_contR, m_residualFuncY, m_addFuncX);
@@ -306,16 +295,15 @@ public class ExtendedKalmanFilter void correct(
Nat rows,
Matrix u,
Matrix y,
BiFunction, Matrix, Matrix> h,
- Matrix R) {
- correct(rows, u, y, h, R, Matrix::minus, Matrix::plus);
+ Matrix contR) {
+ correct(rows, u, y, h, contR, Matrix::minus, Matrix::plus);
}
/**
@@ -330,22 +318,21 @@ public class ExtendedKalmanFilter void correct(
Nat rows,
Matrix u,
Matrix y,
BiFunction, Matrix, Matrix> h,
- Matrix R,
+ Matrix contR,
BiFunction, Matrix, Matrix> residualFuncY,
BiFunction, Matrix, Matrix> addFuncX) {
final var C = NumericalJacobian.numericalJacobianX(rows, m_states, h, m_xHat, u);
- final var discR = Discretization.discretizeR(R, m_dtSeconds);
+ final var discR = Discretization.discretizeR(contR, m_dtSeconds);
final var S = C.times(m_P).times(C.transpose()).plus(discR);
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 a6c298bfe3..b7a4ce4d28 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
@@ -29,18 +29,15 @@ import edu.wpi.first.math.system.LinearSystem;
* https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control
* theory".
*/
-@SuppressWarnings("ClassTypeParameterName")
public class KalmanFilter {
private final Nat m_states;
private final LinearSystem m_plant;
/** The steady-state Kalman gain matrix. */
- @SuppressWarnings("MemberName")
private final Matrix m_K;
/** The state estimate. */
- @SuppressWarnings("MemberName")
private Matrix m_xHat;
/**
@@ -54,7 +51,6 @@ public class KalmanFilter states,
Nat outputs,
@@ -185,7 +181,6 @@ public class KalmanFilter u, double dtSeconds) {
this.m_xHat = m_plant.calculateX(m_xHat, u, dtSeconds);
}
@@ -196,7 +191,6 @@ public class KalmanFilter u, Matrix y) {
final var C = m_plant.getC();
final var D = m_plant.getD();
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java
index 89f35e5eb3..c0c399035c 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanFilterLatencyCompensator.java
@@ -35,7 +35,6 @@ public class KalmanFilterLatencyCompensator observer,
Matrix u,
@@ -60,7 +59,6 @@ public class KalmanFilterLatencyCompensator void applyPastGlobalMeasurement(
Nat rows,
KalmanTypeFilter observer,
@@ -165,14 +163,12 @@ public class KalmanFilterLatencyCompensator xHat;
public final Matrix errorCovariances;
public final Matrix inputs;
public final Matrix localMeasurements;
- @SuppressWarnings("ParameterName")
private ObserverSnapshot(
KalmanTypeFilter observer, Matrix u, Matrix localY) {
this.xHat = observer.getXhat();
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
index 3fd3957d71..7a100f5325 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/KalmanTypeFilter.java
@@ -8,7 +8,6 @@ import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Num;
import edu.wpi.first.math.numbers.N1;
-@SuppressWarnings({"ParameterName", "InterfaceTypeParameterName"})
interface KalmanTypeFilter {
Matrix getP();
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
index c8dbdedbf0..3883a9bb82 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDrivePoseEstimator.java
@@ -110,7 +110,6 @@ public class MecanumDrivePoseEstimator {
* theta]ᵀ, with units in meters and radians.
* @param nominalDtSeconds The time in seconds between each robot loop.
*/
- @SuppressWarnings("ParameterName")
public MecanumDrivePoseEstimator(
Rotation2d gyroAngle,
Pose2d initialPoseMeters,
@@ -290,7 +289,6 @@ public class MecanumDrivePoseEstimator {
* @param wheelSpeeds The current speeds of the mecanum drive wheels.
* @return The estimated pose of the robot in meters.
*/
- @SuppressWarnings("LocalVariableName")
public Pose2d updateWithTime(
double currentTimeSeconds, Rotation2d gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds) {
double dt = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : m_nominalDt;
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 470f560e9e..277b085a26 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
@@ -75,7 +75,6 @@ public class MerweScaledSigmaPoints {
* @return Two dimensional array of sigma points. Each column contains all of the sigmas for one
* dimension in the problem space. Ordered by Xi_0, Xi_{1..n}, Xi_{n+1..2n}.
*/
- @SuppressWarnings({"ParameterName", "LocalVariableName"})
public Matrix squareRootSigmaPoints(Matrix x, Matrix s) {
double lambda = Math.pow(m_alpha, 2) * (m_states.getNum() + m_kappa) - m_states.getNum();
double eta = Math.sqrt(lambda + m_states.getNum());
@@ -101,7 +100,6 @@ public class MerweScaledSigmaPoints {
*
* @param beta Incorporates prior knowledge of the distribution of the mean.
*/
- @SuppressWarnings("LocalVariableName")
private void computeWeights(double beta) {
double lambda = Math.pow(m_alpha, 2) * (m_states.getNum() + m_kappa) - m_states.getNum();
double c = 0.5 / (m_states.getNum() + lambda);
diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
index 7c205de2e6..1023ef7a0f 100644
--- a/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
+++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator.java
@@ -110,7 +110,6 @@ public class SwerveDrivePoseEstimator {
* theta]ᵀ, with units in meters and radians.
* @param nominalDtSeconds The time in seconds between each robot loop.
*/
- @SuppressWarnings("ParameterName")
public SwerveDrivePoseEstimator(
Rotation2d gyroAngle,
Pose2d initialPoseMeters,
@@ -288,7 +287,6 @@ public class SwerveDrivePoseEstimator {
* @param moduleStates The current velocities and rotations of the swerve modules.
* @return The estimated pose of the robot in meters.
*/
- @SuppressWarnings("LocalVariableName")
public Pose2d updateWithTime(
double currentTimeSeconds, Rotation2d gyroAngle, SwerveModuleState... moduleStates) {
double dt = m_prevTimeSeconds >= 0 ? currentTimeSeconds - m_prevTimeSeconds : m_nominalDt;
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 c65be03296..410c619efa 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
@@ -38,7 +38,6 @@ import org.ejml.simple.SimpleMatrix;
* This class implements a square-root-form unscented Kalman filter (SR-UKF). For more
* information about the SR-UKF, see https://www.researchgate.net/publication/3908304.
*/
-@SuppressWarnings({"MemberName", "ClassTypeParameterName"})
public class UnscentedKalmanFilter
implements KalmanTypeFilter {
private final Nat m_states;
@@ -73,7 +72,6 @@ public class UnscentedKalmanFilter states,
Nat