From e404907ec20a837a072d6cecceee3dbc5d3ee087 Mon Sep 17 00:00:00 2001 From: Jade Turner Date: Sun, 1 Dec 2024 19:43:56 +0800 Subject: [PATCH] Add pmd and fix warnings Signed-off-by: Jade Turner --- .gitattributes | 1 - .github/workflows/ci.yml | 41 ++++++ build.gradle | 17 ++- pmd-ruleset.xml | 125 ++++++++++++++++++ src/main/java/frc/robot/Robot.java | 5 +- .../frc/robot/generated/BuildConstants.java | 17 +++ .../frc/robot/subsystems/drive/Drive.java | 2 + .../frc/robot/subsystems/drive/DriveIO.java | 10 +- .../robot/subsystems/drive/DriveIOCTRE.java | 15 +-- .../robot/subsystems/shooter/ShooterIO.java | 8 +- .../subsystems/vision/VisionIOLimelight.java | 4 +- .../robot/subsystems/vision/VisionIOSim.java | 2 +- src/main/java/frc/robot/util/Util.java | 2 +- .../frc/robot/generated}/BuildConstants.java | 12 +- 14 files changed, 223 insertions(+), 38 deletions(-) create mode 100644 .github/workflows/ci.yml create mode 100644 pmd-ruleset.xml create mode 100644 src/main/java/frc/robot/generated/BuildConstants.java rename src/main/java/{frc/robot => generated/frc/robot/generated}/BuildConstants.java (54%) diff --git a/.gitattributes b/.gitattributes index 0347a09..220f268 100644 --- a/.gitattributes +++ b/.gitattributes @@ -6,6 +6,5 @@ *.traj text eol=lf *.chor text eol=lf src/main/java/frc/robot/generated/** linguist-generated -src/main/java/frc/robot/BuildConstants.java linguist-generated *.traj linguist-generated *.chor linguist-generated diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml new file mode 100644 index 0000000..e4c21b7 --- /dev/null +++ b/.github/workflows/ci.yml @@ -0,0 +1,41 @@ +name: Build + +on: [pull_request, push] + +jobs: + build: + name: "Build Java" + runs-on: ubuntu-latest + container: wpilib/roborio-cross-ubuntu:2024-22.04 + steps: + - uses: actions/checkout@v4 + - name: Compile robot code + run: ./gradlew build + + format: + name: "Lint and Format Java" + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + - name: Fetch all history and metadata + run: | + git checkout -b pr + git branch -f master origin/master + - uses: actions/setup-java@v4 + with: + java-version: 17 + distribution: temurin + - uses: gradle/gradle-build-action@v3 + - uses: actions/setup-python@v5 + with: + python-version: 3.8 + - name: Install wpiformat + run: pip3 install wpiformat + - name: Run + run: wpiformat + - name: Check output + run: git --no-pager diff --exit-code HEAD + - name: Run spotless + run: ./gradlew build -PwithJavaFormat diff --git a/build.gradle b/build.gradle index ed436e4..713fcac 100644 --- a/build.gradle +++ b/build.gradle @@ -101,8 +101,8 @@ dependencies { // Create version file project.compileJava.dependsOn(createVersionFile) gversion { - srcDir = "src/main/java/" - classPackage = "frc.robot" + srcDir = "src/main/java/generated/" + classPackage = "frc.robot.generated" className = "BuildConstants" dateFormat = "yyyy-MM-dd HH:mm:ss z" timeZone = "Australia/Perth" @@ -152,7 +152,7 @@ spotless { java { target fileTree('.') { include '**/*.java' - exclude '**/build/**', '**/build-*/**' + exclude '**/build/**', '**/build-*/**', 'src/main/java/generated/**' } toggleOffOn() googleJavaFormat() @@ -190,3 +190,14 @@ spotless { endWithNewline() } } + +apply plugin: "pmd" + +pmd { + toolVersion = "7.3.0" + consoleOutput = true + sourceSets = [project.sourceSets["main"]] + reportsDir = file("${project.buildDir}/reports/pmd") + ruleSetFiles = files(file("$rootDir/pmd-ruleset.xml")) + ruleSets = [] +} diff --git a/pmd-ruleset.xml b/pmd-ruleset.xml new file mode 100644 index 0000000..3403dbd --- /dev/null +++ b/pmd-ruleset.xml @@ -0,0 +1,125 @@ + + + + PMD Ruleset for Curtin FRC Projects + + .*/*JNI.* + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Use Objects.requireNonNull() instead of throwing a + NullPointerException yourself. + + + + + + + + 3 + + + + + diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index f70c1a5..f673927 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -24,6 +24,7 @@ import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction; +import frc.robot.generated.BuildConstants; import frc.robot.generated.TunerConstants; import frc.robot.subsystems.drive.Drive; import frc.robot.subsystems.drive.DriveIO; @@ -48,9 +49,9 @@ import org.littletonrobotics.urcl.URCL; public class Robot extends LoggedRobot { - private double MaxSpeed = + private final double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed - private double MaxAngularRate = + private final double MaxAngularRate = RotationsPerSecond.of(0.75) .in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity diff --git a/src/main/java/frc/robot/generated/BuildConstants.java b/src/main/java/frc/robot/generated/BuildConstants.java new file mode 100644 index 0000000..4b35601 --- /dev/null +++ b/src/main/java/frc/robot/generated/BuildConstants.java @@ -0,0 +1,17 @@ +package frc.robot; + +/** Automatically generated file containing build version information. */ +public final class BuildConstants { + public static final String MAVEN_GROUP = ""; + public static final String MAVEN_NAME = "2025-Reefscape"; + public static final String VERSION = "unspecified"; + public static final int GIT_REVISION = 3; + public static final String GIT_SHA = "a19e6abe401ffc7d43c87ddc67ae93211b27a8ab"; + public static final String GIT_DATE = "2024-12-01 19:28:10 AWST"; + public static final String GIT_BRANCH = "master"; + public static final String BUILD_DATE = "2024-12-01 19:33:24 AWST"; + public static final long BUILD_UNIX_TIME = 1733052804994L; + public static final int DIRTY = 1; + + private BuildConstants() {} +} diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index 206a660..f18e728 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -66,6 +66,7 @@ public boolean isTeleopAtSetpoint() { * SysId routine for characterizing steer. This is used to find PID gains for * the steer motors. */ + @SuppressWarnings("PMD.UnusedPrivateField") private final SysIdRoutine m_sysIdRoutineSteer = new SysIdRoutine( new SysIdRoutine.Config( @@ -84,6 +85,7 @@ public boolean isTeleopAtSetpoint() { * See the documentation of SwerveRequest.SysIdSwerveRotation for info on * importing the log to SysId. */ + @SuppressWarnings("PMD.UnusedPrivateField") private final SysIdRoutine m_sysIdRoutineRotation = new SysIdRoutine( new SysIdRoutine.Config( diff --git a/src/main/java/frc/robot/subsystems/drive/DriveIO.java b/src/main/java/frc/robot/subsystems/drive/DriveIO.java index 7ed8153..3df2fa1 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveIO.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveIO.java @@ -18,13 +18,13 @@ public static class DriveIOInputs { public SwerveModuleState[] moduleTargetStates = new SwerveModuleState[4]; public Pose2d pose = new Pose2d(); public ChassisSpeeds speeds = new ChassisSpeeds(); - public double odometryPeriodSeconds = 0.0; - public int successfulDaqs = 0; - public int failedDaqs = 0; + public double odometryPeriodSeconds; + public int successfulDaqs; + public int failedDaqs; - public double gyroRate = 0.0; + public double gyroRate; public Rotation3d rotation3d = new Rotation3d(); - public boolean odometryIsValid = false; + public boolean odometryIsValid; } public default void updateInputs(DriveIOInputs inputs) {} diff --git a/src/main/java/frc/robot/subsystems/drive/DriveIOCTRE.java b/src/main/java/frc/robot/subsystems/drive/DriveIOCTRE.java index 0b67e50..29af006 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveIOCTRE.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveIOCTRE.java @@ -4,8 +4,6 @@ import com.ctre.phoenix6.swerve.SwerveDrivetrain; import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants; import com.ctre.phoenix6.swerve.SwerveModuleConstants; -import com.ctre.phoenix6.swerve.SwerveRequest; -import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.wpilibj.Notifier; import edu.wpi.first.wpilibj.RobotController; @@ -13,9 +11,10 @@ * Class that extends the Phoenix SwerveDrivetrain class and implements subsystem so it can be used * in command-based projects easily. */ +@SuppressWarnings("PMD.SingularField") public class DriveIOCTRE extends SwerveDrivetrain implements DriveIO { private static final double kSimLoopPeriod = 0.005; // 5 ms - private Notifier m_simNotifier = null; + private Notifier m_simNotifier; private double m_lastSimTime; public DriveIOCTRE( @@ -55,16 +54,6 @@ public void updateInputs(DriveIOInputs inputs) { inputs.odometryIsValid = isOdometryValid(); } - @Override - public void resetPose(Pose2d pose) { - super.resetPose(pose); - } - - @Override - public void setControl(SwerveRequest request) { - super.setControl(request); - } - private void startSimThread() { m_lastSimTime = Utils.getCurrentTimeSeconds(); diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java index e6c2f6f..1a1d018 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterIO.java @@ -5,10 +5,10 @@ public interface ShooterIO { @AutoLog public static class ShooterIOInputs { - public double position = 0.0; - public double velocity = 0.0; - public double appliedVolts = 0.0; - public double currentAmps = 0.0; + public double position; + public double velocity; + public double appliedVolts; + public double currentAmps; } /** Updates the set of loggable inputs. */ diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java index 3e01f43..0cb1e4f 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOLimelight.java @@ -12,7 +12,7 @@ public class VisionIOLimelight implements VisionIO { private final NetworkTable impl; private final DoubleArraySubscriber botpose; - double[] validIds = null; + double[] validIds; private final String camera; public VisionIOLimelight(String camera) { @@ -41,6 +41,6 @@ public void updateInputs(VisionIOInputs inputs) { @Override public void setValidIds(double[] validIds) { impl.getDoubleArrayTopic("fiducial_id_filters_set").publish().set(validIds); - this.validIds = validIds; + this.validIds = validIds.clone(); } } diff --git a/src/main/java/frc/robot/subsystems/vision/VisionIOSim.java b/src/main/java/frc/robot/subsystems/vision/VisionIOSim.java index 01ec8c9..d241cde 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionIOSim.java +++ b/src/main/java/frc/robot/subsystems/vision/VisionIOSim.java @@ -56,7 +56,7 @@ public void updateInputs(VisionIOInputs inputs) { inputs.camera = cameraName; var results = camera.getAllUnreadResults(); - if (results.size() > 0) { + if (results.isEmpty()) { var result = results.get(results.size() - 1); if (result.getMultiTagResult().isPresent()) { inputs.estimatedPose = diff --git a/src/main/java/frc/robot/util/Util.java b/src/main/java/frc/robot/util/Util.java index 871ddb5..bafd28c 100644 --- a/src/main/java/frc/robot/util/Util.java +++ b/src/main/java/frc/robot/util/Util.java @@ -5,7 +5,7 @@ import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.util.WPIUtilJNI; -public class Util { +public final class Util { private Util() {} /** Time in milliseconds */ diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/generated/frc/robot/generated/BuildConstants.java similarity index 54% rename from src/main/java/frc/robot/BuildConstants.java rename to src/main/java/generated/frc/robot/generated/BuildConstants.java index ce84121..27cdf40 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/generated/frc/robot/generated/BuildConstants.java @@ -1,4 +1,4 @@ -package frc.robot; +package frc.robot.generated; /** * Automatically generated file containing build version information. @@ -7,12 +7,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "2025-Reefscape"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 1; - public static final String GIT_SHA = "9bf7dbcdc5f4ab1a52da29bfb97fb310e4722d02"; - public static final String GIT_DATE = "2024-12-01 15:18:41 AWST"; + public static final int GIT_REVISION = 3; + public static final String GIT_SHA = "a19e6abe401ffc7d43c87ddc67ae93211b27a8ab"; + public static final String GIT_DATE = "2024-12-01 19:28:10 AWST"; public static final String GIT_BRANCH = "master"; - public static final String BUILD_DATE = "2024-12-01 19:22:02 AWST"; - public static final long BUILD_UNIX_TIME = 1733052122409L; + public static final String BUILD_DATE = "2024-12-01 19:43:18 AWST"; + public static final long BUILD_UNIX_TIME = 1733053398752L; public static final int DIRTY = 1; private BuildConstants(){}