From e9dcabce6241a9af209d48b764a0e812dc252ee6 Mon Sep 17 00:00:00 2001 From: Michael Mikovsky <77305074+Astatin3@users.noreply.github.com> Date: Thu, 24 Oct 2024 17:04:03 -0600 Subject: [PATCH] add changes --- .../java/frc4388/robot/RobotContainer.java | 36 +++++++++++-------- .../robot/subsystems/SwerveModule.java | 7 ++++ 2 files changed, 29 insertions(+), 14 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 8c2a9a7..262a593 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -120,13 +120,16 @@ public class RobotContainer { ); // ! /* Autos */ - private String lastAutoName = "final_red_center_4note_taxi.auto"; + private String lastAutoName = "four_note_taxi_kracken.auto"; private ConfigurableString autoplaybackName = new ConfigurableString("Auto Playback Name", lastAutoName); private neoJoystickPlayback autoPlayback = new neoJoystickPlayback(m_robotSwerveDrive, - () -> autoplaybackName.get(), // lastAutoName + lastAutoName, // () -> autoplaybackName.get(), // lastAutoName new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, - true, false); - + true, true); + + private neoJoystickPlayback amp_shoot = new neoJoystickPlayback(m_robotSwerveDrive, "Amp_shoot.auto", + new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, + false, true); /** * The container for the robot. Contains subsystems, OI devices, and commands. @@ -134,7 +137,7 @@ public class RobotContainer { public RobotContainer() { configureButtonBindings(); configureVirtualButtonBindings(); - new DeferredBlock(() -> m_robotSwerveDrive.resetGyro()); + new DeferredBlock(() -> m_robotSwerveDrive.resetGyroFlip()); DriverStation.silenceJoystickConnectionWarning(true); // CameraServer.startAutomaticCapture(); @@ -147,6 +150,7 @@ public class RobotContainer { true); }, m_robotSwerveDrive) .withName("SwerveDrive DefaultCommand")); + m_robotSwerveDrive.setToSlow(); // ! Swerve Drive One Module Test // m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> { @@ -164,12 +168,12 @@ public class RobotContainer { // continually sends updates to the Blinkin LED controller to keep the lights on // m_robotLED.setDefaultCommand(new RunCommand(() -> m_robotLED.updateLED(), m_robotLED)); - m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> { - m_robotSwerveDrive.driveWithInput( - getDeadbandedDriverController().getLeft(), - getDeadbandedDriverController().getRight(), - true); - }, m_robotSwerveDrive)); + // m_robotSwerveDrive.setDefaultCommand(new RunCommand(() -> { + // m_robotSwerveDrive.driveWithInput( + // getDeadbandedDriverController().getLeft(), + // getDeadbandedDriverController().getRight(), + // true); + // }, m_robotSwerveDrive)); @@ -187,7 +191,7 @@ public class RobotContainer { // ? /* Driver Buttons */ DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.A_BUTTON) - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive)); + .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip())); // ! /* Speed */ new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final @@ -254,8 +258,12 @@ public class RobotContainer { .onTrue(new InstantCommand(() -> m_robotClimber.climbIn())) .onFalse(new InstantCommand(() -> m_robotClimber.stopClimb())); - new Trigger(() -> getDeadbandedOperatorController().getPOV() == 0) - .onTrue(new InstantCommand(() -> m_robotIntake.ampOuttake(0.5))); + // new Trigger(() -> getDeadbandedOperatorController().getPOV() == 0) + // .onTrue(new InstantCommand(() -> m_robotIntake.ampOuttake(0.5))); + + new Trigger(() -> getDeadbandedOperatorController().getPOV() != -1) + .onTrue(amp_shoot) + .onFalse(new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter, m_robotSwerveDrive)); // ? /* Programer Buttons (Controller 3)*/ diff --git a/src/main/java/frc4388/robot/subsystems/SwerveModule.java b/src/main/java/frc4388/robot/subsystems/SwerveModule.java index 8042080..007918e 100644 --- a/src/main/java/frc4388/robot/subsystems/SwerveModule.java +++ b/src/main/java/frc4388/robot/subsystems/SwerveModule.java @@ -18,6 +18,7 @@ import com.ctre.phoenix6.StatusSignal; import com.ctre.phoenix6.Utils; import com.ctre.phoenix6.configs.CANcoderConfiguration; import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs; +import com.ctre.phoenix6.configs.CurrentLimitsConfigs; import com.ctre.phoenix6.configs.FeedbackConfigs; import com.ctre.phoenix6.configs.MotorOutputConfigs; import com.ctre.phoenix6.configs.OpenLoopRampsConfigs; @@ -73,6 +74,12 @@ public class SwerveModule extends SubsystemBase { new MotorOutputConfigs() .withNeutralMode(NeutralModeValue.Brake) .withDutyCycleNeutralDeadband(SwerveDriveConstants.Configurations.NEUTRAL_DEADBAND) + ).withCurrentLimits( + new CurrentLimitsConfigs() + .withStatorCurrentLimit(110) + .withStatorCurrentLimitEnable(true) + .withSupplyCurrentLimit(110) + .withSupplyCurrentLimitEnable(true) ); driveMotor.getConfigurator().apply(motorCfg);