From 5691fa73ac0d8eed8e2f7a6b8f26ee13c10ecda6 Mon Sep 17 00:00:00 2001 From: Mz Date: Thu, 22 Feb 2024 22:07:44 -0600 Subject: [PATCH] spotless --- src/main/java/frc/robot/RobotContainer.java | 22 ++++++++++++------- .../frc/robot/subsystems/sticks/Sticks.java | 10 ++------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 785d98f..505ca61 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -207,7 +207,10 @@ private void configureButtonBindings() { .a() .whileTrue( Commands.startEnd( - () -> sFlywheel.runVelocity(-flywheelSpeedInput.get()), // ! Is the smartdashboard thing permanent? surely not? + () -> + sFlywheel.runVelocity( + -flywheelSpeedInput + .get()), // ! Is the smartdashboard thing permanent? surely not? sFlywheel::stop, sFlywheel)); driverController @@ -221,7 +224,7 @@ private void configureButtonBindings() { () -> sIntake.runVelocity(-Constants.IntakeConstants.velocity), sIntake::stop, sIntake)); - + driverController .b() .whileFalse(Commands.startEnd(() -> sIntake.runVelocity(0), sIntake::stop, sIntake)); @@ -240,20 +243,23 @@ private void configureButtonBindings() { operatorController .a() .whileTrue( - Commands.startEnd(() -> sClimber.runTargetPosition(0), sClimber::stop, sClimber)); + Commands.startEnd(() -> sClimber.runTargetPosition(0), sClimber::stop, sClimber)); operatorController .b() .whileTrue( - Commands.startEnd(() -> sClimber.runTargetPosition(0.55), sClimber::stop, sClimber)); // !Testing numbers + Commands.startEnd( + () -> sClimber.runTargetPosition(0.55), + sClimber::stop, + sClimber)); // !Testing numbers operatorController .x() - .whileTrue( - Commands.startEnd(() -> sSticks.runTargetAngle(0.0), sSticks::stop, sSticks)); + .whileTrue(Commands.startEnd(() -> sSticks.runTargetAngle(0.0), sSticks::stop, sSticks)); operatorController .y() .whileTrue( - Commands.startEnd(() -> sSticks.runTargetAngle(0.5), sSticks::stop, sSticks)); // !Testing numbers -} + Commands.startEnd( + () -> sSticks.runTargetAngle(0.5), sSticks::stop, sSticks)); // !Testing numbers + } /** * Use this to pass the autonomous command to the main {@link Robot} class. diff --git a/src/main/java/frc/robot/subsystems/sticks/Sticks.java b/src/main/java/frc/robot/subsystems/sticks/Sticks.java index c54d2a6..af006c4 100644 --- a/src/main/java/frc/robot/subsystems/sticks/Sticks.java +++ b/src/main/java/frc/robot/subsystems/sticks/Sticks.java @@ -13,7 +13,6 @@ package frc.robot.subsystems.sticks; -import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.EnvironmentalConstants; @@ -58,10 +57,7 @@ public void runVolts(double volts) { io.setVoltage(volts); } - /** - * Run closed loop at the specified velocity. - * Not used. - * */ + /** Run closed loop at the specified velocity. Not used. */ // public void runVelocity(double velocityRPM) { // var velocityRadPerSec = Units.rotationsPerMinuteToRadiansPerSecond(velocityRPM); // io.setVelocity(velocityRadPerSec, ffModel.calculate(velocityRadPerSec)); @@ -79,9 +75,7 @@ public void runTargetAngle(double position) { io.setTargetAngle(position); } - /** - Sets a target velocity. - */ + /** Sets a target velocity. */ // public void runTargetVelocity(double targetVelocity) { // io.setTargetAngle( // inputs.targetPositionRad