Skip to content

Commit

Permalink
spotless
Browse files Browse the repository at this point in the history
  • Loading branch information
cherriae committed Jan 20, 2024
1 parent 56197b6 commit 301b7f9
Show file tree
Hide file tree
Showing 14 changed files with 1,138 additions and 1,113 deletions.
41 changes: 40 additions & 1 deletion 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 "2024.1.1"
id 'com.diffplug.spotless' version '6.20.0'
}

java {
Expand Down Expand Up @@ -77,7 +78,11 @@ wpi.sim.addDriverstation()
// in order to make them all available at runtime. Also adding the manifest so WPILib
// knows where to look for our Robot Class.
jar {
from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } }
from {
configurations.runtimeClasspath.collect {
it.isDirectory() ? it : zipTree(it)
}
}
from sourceSets.main.allSource
manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS)
duplicatesStrategy = DuplicatesStrategy.INCLUDE
Expand All @@ -92,3 +97,37 @@ wpi.java.configureTestTasks(test)
tasks.withType(JavaCompile) {
options.compilerArgs.add '-XDstringConcat=inline'
}


spotless {
java {
target fileTree('.') {
include '**/*.java'
exclude '**/build/**', '**/build-*/**'
}
toggleOffOn()
googleJavaFormat()
removeUnusedImports()
trimTrailingWhitespace()
endWithNewline()
}
groovyGradle {
target fileTree('.') {
include '**/*.gradle'
exclude '**/build/**', '**/build-*/**'
}
greclipse()
indentWithSpaces(4)
trimTrailingWhitespace()
endWithNewline()
}
format 'misc', {
target fileTree('.') {
include '**/*.md', '**/.gitignore'
exclude '**/build/**', '**/build-*/**'
}
trimTrailingWhitespace()
indentWithSpaces(2)
endWithNewline()
}
}
17 changes: 8 additions & 9 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,25 +53,24 @@ public static class Physical {

public static final double SWERVE_DRIVE_GEAR_RATIO = 6.75;
public static final double SWERVE_DRIVE_WHEEL_RADIUS = 0.1;
public static final double SWERVE_DRIVE_WHEEL_CIRCUMFERENCE = 2 * Math.PI * SWERVE_DRIVE_WHEEL_RADIUS;

public static final double SWERVE_DRIVE_WHEEL_CIRCUMFERENCE =
2 * Math.PI * SWERVE_DRIVE_WHEEL_RADIUS;

public static final double TALON_TICKS_PER_REVOLUTION = 2048;

public static final SwerveDriveKinematics SWERVE_KINEMATICS = new SwerveDriveKinematics(
new Translation2d(0.292, 0.292),
new Translation2d(0.292, -0.292),
new Translation2d(-0.292, -0.292),
new Translation2d(-0.292, 0.292)
);
public static final SwerveDriveKinematics SWERVE_KINEMATICS =
new SwerveDriveKinematics(
new Translation2d(0.292, 0.292),
new Translation2d(0.292, -0.292),
new Translation2d(-0.292, -0.292),
new Translation2d(-0.292, 0.292));
}

public static class Offsets {
public static final double ENCODER_FRONT_LEFT = -93;
public static final double ENCODER_FRONT_RIGHT = -58;
public static final double ENCODER_BACK_RIGHT = 10;
public static final double ENCODER_BACK_LEFT = 43;

}

public static class Ports {
Expand Down
8 changes: 2 additions & 6 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,6 @@

package frc.robot;

import com.ctre.phoenix6.Orchestra;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
Expand All @@ -20,10 +18,8 @@ public class Robot extends TimedRobot {

private RobotContainer m_robotContainer;

/* Talon FXs to play music through.
More complex music MIDIs will contain several tracks, requiring multiple instruments. */


/* Talon FXs to play music through.
More complex music MIDIs will contain several tracks, requiring multiple instruments. */

/**
* This function is run when the robot is first started up and should be used for any
Expand Down
27 changes: 14 additions & 13 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,24 +5,21 @@

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;

import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.PrintCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.button.CommandPS4Controller;
import frc.robot.commands.shooter.Shooter;
import frc.robot.commands.swerve.BrakeSwerve;
import frc.robot.commands.swerve.ResetGyro;
import frc.robot.commands.swerve.ResetPose;
import frc.robot.commands.swerve.TeleopDrive;
import frc.robot.commands.swerve.ToggleSwerveOrient;
import frc.robot.subsystems.ShooterSubsystem;
import frc.robot.subsystems.SwerveDriveSubsystem;
import frc.robot.subsystems.VisionSubsystem;
import frc.robot.subsystems.ShooterSubsystem;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
Expand All @@ -36,7 +33,8 @@ public class RobotContainer {
private final SwerveDriveSubsystem _swerveDrive = new SwerveDriveSubsystem(_visionSubsystem);
private final ShooterSubsystem _shooterSubsystem = new ShooterSubsystem();
// controllers (for driver and operator)
private final CommandPS4Controller _driveController = new CommandPS4Controller(Constants.Ports.DRIVER_CONTROLLER);
private final CommandPS4Controller _driveController =
new CommandPS4Controller(Constants.Ports.DRIVER_CONTROLLER);

// slew rate limiters applied to joysticks
private final SlewRateLimiter _driveFilterLeftX = new SlewRateLimiter(4);
Expand All @@ -55,12 +53,12 @@ public RobotContainer() {
NamedCommands.registerCommand("waitCommand", new WaitCommand(3));
NamedCommands.registerCommand("brakeSwerve", brakeSwerve);

_swerveDrive.setDefaultCommand(new TeleopDrive(
_swerveDrive,
() -> -_driveFilterLeftY.calculate(_driveController.getLeftY()),
() -> -_driveFilterLeftX.calculate(_driveController.getLeftX()),
() -> -_driveFilterRightX.calculate(_driveController.getRightX())
));
_swerveDrive.setDefaultCommand(
new TeleopDrive(
_swerveDrive,
() -> -_driveFilterLeftY.calculate(_driveController.getLeftY()),
() -> -_driveFilterLeftX.calculate(_driveController.getLeftX()),
() -> -_driveFilterRightX.calculate(_driveController.getRightX())));

// configure trigger bindings
configureBindings();
Expand All @@ -78,9 +76,12 @@ private void configureBindings() {
_driveController.cross().whileTrue(new BrakeSwerve(_swerveDrive, 0));
}

/** @return The Command to schedule for auton. */
/**
* @return The Command to schedule for auton.
*/
public Command getAutonCommand() {
_swerveDrive.fieldOriented = false; // make sure swerve is robot-relative for pathplanner to work
_swerveDrive.fieldOriented =
false; // make sure swerve is robot-relative for pathplanner to work

return autonChooser.getSelected();
}
Expand Down
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/commands/swerve/BrakeSwerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,7 @@ public void execute() {
new SwerveModuleState(0, Rotation2d.fromDegrees(-45))
};

_swerveDrive.setStates(
states
);
_swerveDrive.setStates(states);
}

// Called once the command ends or is interrupted.
Expand Down
1 change: 0 additions & 1 deletion src/main/java/frc/robot/commands/swerve/ResetGyro.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.SwerveDriveSubsystem;


/**
* @author Elvis Osmanov
*/
Expand Down
22 changes: 12 additions & 10 deletions src/main/java/frc/robot/commands/swerve/TeleopDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,12 @@

package frc.robot.commands.swerve;

import java.util.function.DoubleSupplier;

import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.subsystems.SwerveDriveSubsystem;
import frc.robot.utils.UtilFuncs;
import java.util.function.DoubleSupplier;

/**
* Drive the swerve chassis based on teleop joystick input
Expand All @@ -26,7 +25,11 @@ public class TeleopDrive extends Command {
private final DoubleSupplier _rotationSpeed;

/** Creates a new TeleopDrive. */
public TeleopDrive(SwerveDriveSubsystem swerveDrive, DoubleSupplier xSpeed, DoubleSupplier ySpeed, DoubleSupplier rotationSpeed) {
public TeleopDrive(
SwerveDriveSubsystem swerveDrive,
DoubleSupplier xSpeed,
DoubleSupplier ySpeed,
DoubleSupplier rotationSpeed) {
_swerveDrive = swerveDrive;

_xSpeed = xSpeed;
Expand All @@ -40,8 +43,7 @@ public TeleopDrive(SwerveDriveSubsystem swerveDrive, DoubleSupplier xSpeed, Doub

// Called when the command is initially scheduled.
@Override
public void initialize() {
}
public void initialize() {}

// Called every time the scheduler runs while the command is scheduled.
@Override
Expand All @@ -52,11 +54,11 @@ public void execute() {
double rotationSpeed = UtilFuncs.ApplyDeadband(_rotationSpeed.getAsDouble(), 0.1);

// drive the swerve chassis subsystem
_swerveDrive.driveChassis(new ChassisSpeeds(
xSpeed * Constants.Speeds.SWERVE_DRIVE_MAX_SPEED * Constants.Speeds.SWERVE_DRIVE_COEFF,
ySpeed * Constants.Speeds.SWERVE_DRIVE_MAX_SPEED * Constants.Speeds.SWERVE_DRIVE_COEFF,
rotationSpeed * Constants.Speeds.SWERVE_DRIVE_MAX_ANGULAR_SPEED
));
_swerveDrive.driveChassis(
new ChassisSpeeds(
xSpeed * Constants.Speeds.SWERVE_DRIVE_MAX_SPEED * Constants.Speeds.SWERVE_DRIVE_COEFF,
ySpeed * Constants.Speeds.SWERVE_DRIVE_MAX_SPEED * Constants.Speeds.SWERVE_DRIVE_COEFF,
rotationSpeed * Constants.Speeds.SWERVE_DRIVE_MAX_ANGULAR_SPEED));
}

// Called once the command ends or is interrupted.
Expand Down
19 changes: 9 additions & 10 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,37 +3,36 @@

package frc.robot.subsystems;

import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;

/**
* @author Elvis Osmanov
* @author Peleh Liu
* @author Cherine Soewingjo
*/
public class ShooterSubsystem extends SubsystemBase {
private CANSparkMax _leftMotor = new CANSparkMax(Constants.CAN.SHOOTER_LEFT, MotorType.kBrushless);
private CANSparkMax _rightMotor = new CANSparkMax(Constants.CAN.SHOOTER_RIGHT, MotorType.kBrushless);
private CANSparkMax _leftMotor =
new CANSparkMax(Constants.CAN.SHOOTER_LEFT, MotorType.kBrushless);
private CANSparkMax _rightMotor =
new CANSparkMax(Constants.CAN.SHOOTER_RIGHT, MotorType.kBrushless);

/** Creates a new ShooterSubsystem. */
public ShooterSubsystem() {
}

public ShooterSubsystem() {}

@Override
public void periodic() {
// This method will be called once per scheduler run
}

public void spinMotor(){
public void spinMotor() {
_leftMotor.set(-1.0);
_rightMotor.set(1.0);
}

public void stopMotors(){
public void stopMotors() {
_leftMotor.set(0);
_rightMotor.set(0);
}
Expand Down
Loading

0 comments on commit 301b7f9

Please sign in to comment.