Skip to content

Commit

Permalink
fix linting errors
Browse files Browse the repository at this point in the history
  • Loading branch information
wilsonwatson committed Nov 14, 2023
1 parent 9890e83 commit e73e229
Show file tree
Hide file tree
Showing 41 changed files with 102 additions and 86 deletions.
9 changes: 7 additions & 2 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2023.4.3"
id "checkstyle"
}

sourceCompatibility = JavaVersion.VERSION_11
Expand Down Expand Up @@ -83,7 +84,7 @@ dependencies {
testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2'
testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2'

// annotationProcessor project(":checker")
annotationProcessor project(":checker")
def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
annotationProcessor "org.littletonrobotics.akit.junction:junction-autolog:$akitJson.version"
}
Expand Down Expand Up @@ -117,8 +118,8 @@ tasks.withType(JavaCompile) {
// only run in GH actions
if (System.getenv("GITHUB_ACTOR") != null && !System.getenv("GITHUB_ACTOR").equals("")) {
options.compilerArgs << "-Xplugin:rchk"
outputs.upToDateWhen { false } // Force recompile, even if source file hasn't changed
}
outputs.upToDateWhen { false } // Force recompile, even if source file hasn't changed
}

javadoc {
Expand All @@ -130,3 +131,7 @@ javadoc {
"</script>"
}
}

checkstyle {
config = project.resources.text.fromFile("checks.xml")
}
Empty file modified checker/build.gradle
100755 → 100644
Empty file.
Empty file.
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ public boolean process(Set<? extends TypeElement> arg0, RoundEnvironment roundEn
if (fatal) {
throw new RuntimeException("Checks failed!");
}
return true;
return false;
}

}
Empty file modified checker/src/main/java/org/frc5572/robotools/checks/Check.java
100755 → 100644
Empty file.
Empty file modified checker/src/main/java/org/frc5572/robotools/checks/IOCheck.java
100755 → 100644
Empty file.
2 changes: 2 additions & 0 deletions src/main/java/frc/lib/util/swerve/SwerveModuleIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,10 @@
import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.DemandType;

/** IO Class for SwerveModule */
public interface SwerveModuleIO {

/** Inputs Class for SwerveModule */
@AutoLog
public static class SwerveModuleInputs {
public double angleEncoderValue;
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/frc/lib/util/swerve/SwerveModuleReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,9 @@
import frc.robot.Constants;
import frc.robot.Robot;

/**
* Implementation for the real robot
*/
public class SwerveModuleReal implements SwerveModuleIO {

private TalonFX angleMotor; // Output
Expand All @@ -17,6 +20,9 @@ public class SwerveModuleReal implements SwerveModuleIO {

private SwerveModuleConstants constants;

/**
* Initializer for real swerve module. Configures with defaults.
*/
public SwerveModuleReal(SwerveModuleConstants constants) {
this.constants = constants;

Expand Down
19 changes: 0 additions & 19 deletions src/main/java/frc/robot/BuildConstants.java

This file was deleted.

3 changes: 3 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,9 @@ public final class Constants {
public static final int DRIVER_ID = 0;
public static final int OPERATOR_ID = 1;

/** number of seconds between each loop iteration. */
public static final double kDefaultPeriod = 0.02;

/**
* Motor CAN id's. PID constants for Swerve Auto Holonomic Drive Controller.
*/
Expand Down
12 changes: 11 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ public class Robot extends LoggedRobot {
public static int column = 0;
public static UsbCamera camera = CameraServer.startAutomaticCapture("Magazine Camera", 0);

PowerDistribution powerDistribution = null;

// private Ultrasonic ultrasonic = new Ultrasonic();
/**
* This function is run when the robot is first started up and should be used for any
Expand All @@ -48,7 +50,7 @@ public void robotInit() {
if (isReal()) {
logger.addDataReceiver(new WPILOGWriter("/media/sda1"));
logger.addDataReceiver(new NT4Publisher());
new PowerDistribution(1, ModuleType.kRev);
powerDistribution = new PowerDistribution(1, ModuleType.kRev);
} else {
String path = LogFileUtil.findReplayLog();
logger.setReplaySource(new WPILOGReader(path));
Expand Down Expand Up @@ -134,4 +136,12 @@ public void testInit() {
/** This function is called periodically during test mode. */
@Override
public void testPeriodic() {}

@Override
public void close() {
super.close();
if (powerDistribution != null) {
powerDistribution.close();
}
}
}
10 changes: 8 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,9 @@
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.swerve2.SwerveIO;
import frc.robot.subsystems.swerve2.SwerveReal;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntakeIO;
import frc.robot.subsystems.wrist_intake.WristIntakeIOFalcon500;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
Expand Down Expand Up @@ -127,7 +129,7 @@ public class RobotContainer {
public final Swerve s_Swerve;
// private final DropIntake s_dIntake = new DropIntake();
private final Arm s_Arm;
private final WristIntake s_wristIntake = new WristIntake();
private final WristIntake s_wristIntake;

private ArmIO armIO;

Expand All @@ -138,10 +140,14 @@ public RobotContainer(boolean isReal) {
if (isReal) {
armIO = new ArmIOSparkMax(ph);
s_Swerve = new Swerve(new SwerveReal());
s_wristIntake = new WristIntake(new WristIntakeIOFalcon500());
} else {
armIO = new ArmIO() {};
s_Swerve = new Swerve(new SwerveIO() {

});
s_wristIntake = new WristIntake(new WristIntakeIO() {

});
}
s_Arm = new Arm(armIO);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/CrossAndDock.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
import frc.robot.commands.drive.TurnToAngle;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Leaves community, and docks.
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/DoubleScore.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
import frc.robot.commands.wrist.AutoWrist;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Score a second game piece
Expand Down
5 changes: 1 addition & 4 deletions src/main/java/frc/robot/autos/DoubleScore6.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,12 @@
import frc.robot.commands.wrist.AutoWrist;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Score a second game piece
*/
public class DoubleScore6 extends TrajectoryBase {

private double maxVel = 6;
private double maxAccel = 4;
// private double armAngle = -60.0;
// private double wristAngle = 3.0;
Pose2d aprilTag7 = FieldConstants.aprilTags.get(7).toPose2d();
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/MiddleScoreEngage.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import frc.robot.commands.wrist.WristIntakeRelease;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Score one game piece then engage from community side.
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/Score1.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import frc.robot.commands.wrist.WristIntakeRelease;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Score1Dock Auto.
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/Score1Dock.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import frc.robot.commands.wrist.WristIntakeRelease;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Score1Dock Auto.
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/SecondGamePiece.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
import frc.robot.commands.wrist.AutoWrist;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;


/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/SecondGamePiece6.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
import frc.robot.commands.wrist.AutoWrist;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;


/**
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/SecondGamePieceScore.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import frc.robot.commands.wrist.WristIntakeRelease;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Acquire a second game piece after scoring
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/TripleScore.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
import frc.robot.commands.wrist.AutoWrist;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Score three game pieces
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/autos/TripleScore6.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
import frc.robot.commands.wrist.AutoWrist;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Score three game pieces
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/arm/DockArm.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.lib.util.ArmPosition;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Command to dock the arm in the robot
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/arm/ScoreArm.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.lib.util.Scoring;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Command to move arm into scoring position
Expand Down
14 changes: 1 addition & 13 deletions src/main/java/frc/robot/commands/drive/MoveToEngage.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,9 @@
package frc.robot.commands.drive;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.lib.util.FieldConstants;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;


/**
Expand All @@ -25,14 +23,4 @@ public MoveToEngage(Swerve swerve, Arm arm, WristIntake wristIntake) {
ClimbPlatform climbPlatform = new ClimbPlatform(swerve);
addCommands(climbPlatform);
}

/**
* Check if the robot's position is inside the community or center of the field
*
* @return True if the robot is in the middle of the field. False if in the community
*/
private boolean centerField() {
Pose2d pose = FieldConstants.allianceFlip(swerve.getPose());
return pose.getX() > FieldConstants.Community.cableBumpInnerX;
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/drive/MoveToScore.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
import frc.robot.commands.arm.ScoreArm;
import frc.robot.subsystems.arm.Arm;
import frc.robot.subsystems.swerve2.Swerve;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;


/**
Expand Down
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/commands/test/TestArm.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.lib.util.ArmPosition;
import frc.lib.util.Scoring;
import frc.lib.util.Scoring.GamePiece;
import frc.robot.Robot;
Expand All @@ -25,7 +24,6 @@ public void initialize() {
SmartDashboard.putNumber("Targeted Column", Robot.column);
GamePiece gamePiece = Scoring.getGamePiece();
SmartDashboard.putString("Targeted Game Piece", gamePiece.toString());
ArmPosition position = Scoring.getScoreParameters();
// arm.enablePID();
// arm.setArmGoal(position.getArmAngle());
arm.setArmGoal(60);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/wrist/AutoWrist.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.Constants;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Consistent wrist operation for Autonomous.
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/wrist/VariableIntake.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Variable controlled intake speed.
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/wrist/WristIntakeIn.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.Constants;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Command to raise the Drop Down Intake to the top position
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.lib.util.Scoring;
import frc.robot.Constants;
import frc.robot.subsystems.wristIntake.WristIntake;
import frc.robot.subsystems.wrist_intake.WristIntake;

/**
* Command to raise the Drop Down Intake to the top position
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/subsystems/arm/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ public class Arm extends SubsystemBase {
*/
public Arm(ArmIO armIO) {
io = armIO;
io.updateInputs(armInputs);


this.wristPIDController.setIntegratorRange(Constants.Wrist.PID.MIN_INTEGRAL,
Expand Down
Loading

0 comments on commit e73e229

Please sign in to comment.