From 0ca317183a517f47a2f471e4ad18ed23a302c046 Mon Sep 17 00:00:00 2001 From: Programmers Date: Sun, 21 Apr 2024 16:11:54 -0500 Subject: [PATCH] spotless apply --- src/main/java/frc/robot/RobotContainer.java | 12 +++--------- .../robot/commands/movement/SwerveCommand.java | 15 +++++++++++---- 2 files changed, 14 insertions(+), 13 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 72573e9..497aea4 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -23,7 +23,6 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.ConditionalCommand; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup; @@ -32,19 +31,13 @@ import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.commands.control.AimLockWrist; -import frc.robot.commands.control.Climb; import frc.robot.commands.control.GoHome; -import frc.robot.commands.control.IdleShooter; import frc.robot.commands.control.NewShootAmpAuto; import frc.robot.commands.control.ReverseIntake; import frc.robot.commands.control.ShootAmp; import frc.robot.commands.control.ShootSubwoofer; import frc.robot.commands.control.ShootSubwooferFirstHalf; -import frc.robot.commands.control.ShootSubwooferFlat; -import frc.robot.commands.control.ShootTall; import frc.robot.commands.control.StopAll; -import frc.robot.commands.control.amp.FireRevAmp; -import frc.robot.commands.control.amp.PrepRevAmp; import frc.robot.commands.control.auto.AutoAimLockWrist; import frc.robot.commands.control.auto.AutoIdleShooter; import frc.robot.commands.control.auto.InstantShoot; @@ -59,7 +52,6 @@ import frc.robot.commands.movement.CollectNoteAuto; import frc.robot.commands.movement.DriveToNote; import frc.robot.commands.movement.DriveToNoteAuto; -import frc.robot.commands.movement.PointAtAprilTag; import frc.robot.commands.movement.SwerveCommand; import frc.robot.commands.qol.AsyncRumble; import frc.robot.commands.qol.DefaultCANdle; @@ -140,7 +132,9 @@ private void configureDriverController() { .onTrue( new GoHome(ELEVATOR, WRIST, SHOOTER, INTAKE) .andThen(new InstantCommand(() -> WRIST.goHome()))); - DRIVER_CONTROLLER.x().onTrue(new PoopNote(SHOOTER, 1500).andThen(() -> SHOOTER.stopShooter(), SHOOTER)); + DRIVER_CONTROLLER + .x() + .onTrue(new PoopNote(SHOOTER, 1500).andThen(() -> SHOOTER.stopShooter(), SHOOTER)); DRIVER_CONTROLLER .leftBumper() .onTrue( diff --git a/src/main/java/frc/robot/commands/movement/SwerveCommand.java b/src/main/java/frc/robot/commands/movement/SwerveCommand.java index e6d50b5..c885a99 100644 --- a/src/main/java/frc/robot/commands/movement/SwerveCommand.java +++ b/src/main/java/frc/robot/commands/movement/SwerveCommand.java @@ -1,7 +1,6 @@ package frc.robot.commands.movement; import com.ctre.phoenix6.mechanisms.swerve.SwerveRequest; - import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.wpilibj.DriverStation; @@ -25,7 +24,7 @@ */ public class SwerveCommand extends Command { - static private final double MAX_SPEED_TRANSLATION = 2.0; + private static final double MAX_SPEED_TRANSLATION = 2.0; private final PIDController THETA_CONTROLLER; private final IntSupplier POV_DEGREE; @@ -117,9 +116,17 @@ public void execute() { DRIVETRAIN.setControl( DRIVE_REQUEST - .withVelocityX(MathUtil.clamp(xPercentage, -MAX_SPEED_TRANSLATION, MAX_SPEED_TRANSLATION)) // Drive forward with + .withVelocityX( + MathUtil.clamp( + xPercentage, + -MAX_SPEED_TRANSLATION, + MAX_SPEED_TRANSLATION)) // Drive forward with // negative Y (forward) - .withVelocityY(MathUtil.clamp(yPercentage, -MAX_SPEED_TRANSLATION, MAX_SPEED_TRANSLATION)) // Drive left with negative X (left) + .withVelocityY( + MathUtil.clamp( + yPercentage, + -MAX_SPEED_TRANSLATION, + MAX_SPEED_TRANSLATION)) // Drive left with negative X (left) .withRotationalRate(rotationalVelocity)); }