From 9357a6e4d51de09904061f33f5be4fa3d64beda3 Mon Sep 17 00:00:00 2001 From: C4llSiqn Date: Wed, 3 Apr 2024 20:13:23 -0600 Subject: [PATCH 1/4] Code Cleanup, Remove old autos in container. Refactor Intake to be talon only. --- .../java/frc4388/robot/RobotContainer.java | 417 ++++-------------- src/main/java/frc4388/robot/RobotMap.java | 4 - .../commands/Autos/ArmIntakeInTimeout.java | 10 +- .../robot/commands/Autos/AutoBalance.java | 2 +- .../robot/commands/Intake/ArmIntakeIn.java | 6 +- .../java/frc4388/robot/subsystems/Intake.java | 312 ++----------- .../frc4388/utility/DualJoystickButton.java | 22 + 7 files changed, 164 insertions(+), 609 deletions(-) create mode 100644 src/main/java/frc4388/utility/DualJoystickButton.java diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index f0429f8..3e0325c 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -7,14 +7,20 @@ package frc4388.robot; -import org.opencv.video.Video; - -import edu.wpi.first.cameraserver.CameraServer; -import edu.wpi.first.cscore.VideoMode; -import edu.wpi.first.math.geometry.Translation2d; +// Drive Systems import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.GenericHID.RumbleType; +import frc4388.utility.controller.XboxController; +import frc4388.utility.controller.DeadbandedXboxController; +import frc4388.robot.Constants.OIConstants; +import edu.wpi.first.wpilibj2.command.button.JoystickButton; +import edu.wpi.first.wpilibj2.command.button.Trigger; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; + +// Commands import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj2.command.ParallelCommandGroup; @@ -22,30 +28,28 @@ import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; import edu.wpi.first.wpilibj2.command.WaitCommand; import edu.wpi.first.wpilibj2.command.WaitUntilCommand; -import edu.wpi.first.wpilibj2.command.button.JoystickButton; -import edu.wpi.first.wpilibj2.command.button.Trigger; -import frc4388.robot.Constants.IntakeConstants; -import frc4388.robot.Constants.OIConstants; -import frc4388.robot.Constants.ShooterConstants; -//import frc4388.robot.commands.Autos.AutoAlign; + +// Autos import frc4388.robot.commands.Autos.PlaybackChooser; import frc4388.robot.commands.Swerve.JoystickPlayback; import frc4388.robot.commands.Swerve.JoystickRecorder; +import frc4388.utility.controller.VirtualController; import frc4388.robot.commands.Swerve.neoJoystickPlayback; import frc4388.robot.commands.Swerve.neoJoystickRecorder; import frc4388.robot.commands.Intake.ArmIntakeIn; -import frc4388.robot.commands.Autos.ArmIntakeInAuto; +//import frc4388.robot.commands.Autos.AutoAlign; + +// Subsystems import frc4388.robot.subsystems.LED; import frc4388.robot.subsystems.Limelight; import frc4388.robot.subsystems.SwerveDrive; import frc4388.robot.subsystems.Shooter; import frc4388.robot.subsystems.Climber; import frc4388.robot.subsystems.Intake; + +// Utilites import frc4388.utility.DeferredBlock; import frc4388.utility.configurable.ConfigurableString; -import frc4388.utility.controller.DeadbandedXboxController; -import frc4388.utility.controller.VirtualController; -import frc4388.utility.controller.XboxController; /** * This class is where the bulk of the robot should be declared. Since @@ -57,10 +61,12 @@ import frc4388.utility.controller.XboxController; public class RobotContainer { /* RobotMap */ private final RobotMap m_robotMap = new RobotMap(); - + /* Subsystems */ private final LED m_robotLED = new LED(); + private final Intake m_robotIntake = new Intake(m_robotMap.intakeMotor, m_robotMap.pivotMotor); + public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.leftFront, m_robotMap.rightFront, m_robotMap.leftBack, @@ -74,14 +80,11 @@ public class RobotContainer { private final Climber m_robotClimber = new Climber(m_robotMap.climbMotor); - //private final Intake m_robotIntake = new Intake(m_robotMap.intakeMotor, m_robotMap.pivotMotor); - /* Controllers */ private final DeadbandedXboxController m_driverXbox = new DeadbandedXboxController(OIConstants.XBOX_DRIVER_ID); private final DeadbandedXboxController m_operatorXbox = new DeadbandedXboxController(OIConstants.XBOX_OPERATOR_ID); private final DeadbandedXboxController m_autoRecorderXbox = new DeadbandedXboxController(2); - private final Intake m_robotIntake = new Intake(m_robotMap.intakeMotor, m_robotMap.pivotMotor); /* Virtual Controllers */ private final VirtualController m_virtualDriver = new VirtualController(0); @@ -91,23 +94,12 @@ public class RobotContainer { private Command interrupt = new InstantCommand(() -> {}, m_robotIntake, m_robotShooter); private SequentialCommandGroup intakeToShoot = new SequentialCommandGroup( - new InstantCommand(() -> m_robotIntake.talonPIDIn()), + new InstantCommand(() -> m_robotIntake.PIDIn()), new InstantCommand(() -> m_robotShooter.idle()) // new InstantCommand(() -> m_driverXbox.setRumble(RumbleType.kRightRumble, 1.0)).andThen(new WaitCommand(0.2)).andThen(new InstantCommand(() -> m_driverXbox.setRumble(RumbleType.kRightRumble, 0.0))), // new InstantCommand(() -> m_robotShooter.spin()) ); - // private SequentialCommandGroup outtakeToShootFull = new SequentialCommandGroup( - // new InstantCommand(() -> m_robotShooter.spin()), - // new InstantCommand(() -> m_robotIntake.handoff()) - // ); - - // private SequentialCommandGroup intakeInToOut = new SequentialCommandGroup( - // new InstantCommand(() -> m_robotIntake.rotateArmOut2(), m_robotIntake), - // new RunCommand(() -> m_robotIntake.limitNote(), m_robotIntake).until(m_robotIntake.getArmFowardLimitState()), - // new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter) - // ); - // ! Teleop Commands @@ -118,7 +110,7 @@ public class RobotContainer { //autoAlign, new InstantCommand(() -> m_robotShooter.spin()), new WaitCommand(3.0), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), + new InstantCommand(() -> m_robotIntake.handoff(), m_robotIntake), new WaitCommand(3.0), new InstantCommand(() -> m_robotShooter.idle()) // new InstantCommand(() -> autoAlign.reverse()), @@ -134,7 +126,7 @@ public class RobotContainer { private SequentialCommandGroup ejectToShoot = new SequentialCommandGroup( new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), new WaitCommand(0.75), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake) + new InstantCommand(() -> m_robotIntake.handoff(), m_robotIntake) ); private SequentialCommandGroup turnOffShoot = new SequentialCommandGroup( @@ -144,8 +136,8 @@ public class RobotContainer { private SequentialCommandGroup emergencyRetract = new SequentialCommandGroup( interrupt, - new InstantCommand(() -> m_robotIntake.talonPIDIn(), m_robotIntake), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake) + new InstantCommand(() -> m_robotIntake.PIDIn(), m_robotIntake), + new InstantCommand(() -> m_robotIntake.stopIntakeMotors(), m_robotIntake) ); private SequentialCommandGroup ampShoot = new SequentialCommandGroup( @@ -154,137 +146,24 @@ public class RobotContainer { ); // ! /* Autos */ - private Command taxi = new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt"); //new InstantCommand(); - private Command startLeftMoveRight = new InstantCommand(); // new JoystickPlayback(m_robotSwerveDrive, "StartLeftMoveRight.txt"); - private Command startRightMoveLeft = new InstantCommand(); // new JoystickPlayback(m_robotSwerveDrive, "StartRightMoveLeft.txt"); + // private Command taxi = new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt"); private String lastAutoName = "final_red_center_4note_taxi.auto"; private ConfigurableString autoplaybackName = new ConfigurableString("Auto Playback Name", lastAutoName); private neoJoystickPlayback autoPlayback = new neoJoystickPlayback(m_robotSwerveDrive, - lastAutoName, // () -> autoplaybackName.get(), + () -> autoplaybackName.get(), // lastAutoName new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, - true, true); + true, false); - //Help Simplify Shooting - // private SequentialCommandGroup pullInArmtoShoot = new SequentialCommandGroup( - // new InstantCommand(() -> m_robotIntake.talonPIDIn()), - // new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - // new WaitCommand(1.4).asProxy(), - // new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - // new WaitCommand(0.5), - // new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - // new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake) - // ); - - private SequentialCommandGroup oneNoteStartingSpeaker = new SequentialCommandGroup ( - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake), - new WaitCommand(1).asProxy(), - new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt") - ); - private SequentialCommandGroup oneNoteStartingSpeakerStationary = new SequentialCommandGroup ( - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake) - ); - private SequentialCommandGroup oneNoteStartingFromLeft = new SequentialCommandGroup( - startLeftMoveRight.asProxy(), - ejectToShoot.asProxy(), - taxi.asProxy() - ); - private SequentialCommandGroup oneNoteStartingFromRight = new SequentialCommandGroup( - startRightMoveLeft.asProxy(), - ejectToShoot.asProxy(), - taxi.asProxy() - ); - - - private SequentialCommandGroup twoNoteStartingFromSpeaker = new SequentialCommandGroup( - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake), - new ArmIntakeInAuto(m_robotIntake, m_robotShooter, m_robotSwerveDrive), - new InstantCommand(() -> m_robotIntake.talonPIDIn()), - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1.4).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(0.5), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake), - new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt") - // new WaitCommand(1).asProxy(), - // new JoystickPlayback(m_robotSwerveDrive, "TwoNotePrt2.txt"), - // new WaitCommand(0.5).asProxy(), - // new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - // new WaitCommand(1).asProxy(), - // new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - // new WaitCommand(1).asProxy(), - // new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - // new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake) - ); - - private SequentialCommandGroup stayTwoNoteStartingFromSpeaker = new SequentialCommandGroup( - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake), - new ArmIntakeInAuto(m_robotIntake, m_robotShooter, m_robotSwerveDrive), - new InstantCommand(() -> m_robotIntake.talonPIDIn()), - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1.4).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(0.5), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake) - ); - - private SequentialCommandGroup threeNoteStartingFromSpeaker = new SequentialCommandGroup( - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(1).asProxy(), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake), - new ArmIntakeInAuto(m_robotIntake, m_robotShooter, m_robotSwerveDrive), - new InstantCommand(() -> m_robotIntake.talonPIDIn()), - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1.4).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(0.5), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake), - //? Create Another Parallel Command Group :( - new InstantCommand(() -> m_robotIntake.talonPIDIn()), - new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), - new WaitCommand(1.4).asProxy(), - new InstantCommand(() -> m_robotIntake.talonHandoff(), m_robotIntake), - new WaitCommand(0.5), - new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter), - new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake), - new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt") - ); - - private PlaybackChooser playbackChooser = new PlaybackChooser(m_robotSwerveDrive) - .addOption("Taxi Auto", taxi.asProxy()) - .addOption("One Note Auto Starting in Front of Speaker", oneNoteStartingSpeaker.asProxy()) - .addOption("Stay One Note Auto Starting in Front of Speaker", oneNoteStartingSpeakerStationary.asProxy()) - // .addOption("One Note Auto Starting from Left Position", oneNoteStartingFromLeft.asProxy()) - // .addOption("One Note Auto Starting from Right Position", oneNoteStartingFromRight.asProxy()) - .addOption("Two Note Starting in Front of Speaker", twoNoteStartingFromSpeaker.asProxy()) - .addOption("Stay Two Note Starting in Front of Speaker", stayTwoNoteStartingFromSpeaker.asProxy()) - .buildDisplay(); + // private PlaybackChooser playbackChooser = new PlaybackChooser(m_robotSwerveDrive) + // .addOption("Taxi Auto", taxi.asProxy()) + // .addOption("One Note Auto Starting in Front of Speaker", oneNoteStartingSpeaker.asProxy()) + // .addOption("Stay One Note Auto Starting in Front of Speaker", oneNoteStartingSpeakerStationary.asProxy()) + // // .addOption("One Note Auto Starting from Left Position", oneNoteStartingFromLeft.asProxy()) + // // .addOption("One Note Auto Starting from Right Position", oneNoteStartingFromRight.asProxy()) + // .addOption("Two Note Starting in Front of Speaker", twoNoteStartingFromSpeaker.asProxy()) + // .addOption("Stay Two Note Starting in Front of Speaker", stayTwoNoteStartingFromSpeaker.asProxy()) + // .buildDisplay(); @@ -341,14 +220,14 @@ public class RobotContainer { // ? /* Driver Buttons */ - new JoystickButton(getDeadbandedDriverController(), XboxController.A_BUTTON) + DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.A_BUTTON) .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive)); - new JoystickButton(getDeadbandedDriverController(), XboxController.BACK_BUTTON) + DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.BACK_BUTTON) .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightBlue())) .onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180())); - new JoystickButton(getDeadbandedDriverController(), XboxController.START_BUTTON) + DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.START_BUTTON) .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp())) .onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180())); @@ -434,48 +313,48 @@ public class RobotContainer { //? /* Operator Buttons */ - new JoystickButton(getDeadbandedOperatorController(), XboxController.Y_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonPIDIn())) - .onFalse(new InstantCommand(() -> m_robotIntake.talonStopArmMotor())); + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.Y_BUTTON) + .onTrue(new InstantCommand(() -> m_robotIntake.PIDIn())) + .onFalse(new InstantCommand(() -> m_robotIntake.stopArmMotor())); - new JoystickButton(getDeadbandedOperatorController(), XboxController.X_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonPIDOut())) - .onFalse(new InstantCommand(() -> m_robotIntake.talonStopArmMotor())); + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.X_BUTTON) + .onTrue(new InstantCommand(() -> m_robotIntake.PIDOut())) + .onFalse(new InstantCommand(() -> m_robotIntake.stopArmMotor())); - new JoystickButton(getDeadbandedOperatorController(), XboxController.A_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonHandoff())) - .onFalse(new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors())); + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.A_BUTTON) + .onTrue(new InstantCommand(() -> m_robotIntake.handoff())) + .onFalse(new InstantCommand(() -> m_robotIntake.stopIntakeMotors())); - new JoystickButton(getDeadbandedOperatorController(), XboxController.B_BUTTON) + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.B_BUTTON) .onTrue(emergencyRetract); // Override Intake Position encoder: out new JoystickButton(getDeadbandedOperatorController(), XboxController.BACK_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonSetPivotEncoderPosition(-55), m_robotIntake)); + .onTrue(new InstantCommand(() -> m_robotIntake.setPivotEncoderPosition(-55), m_robotIntake)); // Override Intake Position encoder: in new JoystickButton(getDeadbandedOperatorController(), XboxController.START_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonSetPivotEncoderPosition(-6.2), m_robotIntake)); + .onTrue(new InstantCommand(() -> m_robotIntake.setPivotEncoderPosition(-6.2), m_robotIntake)); - new JoystickButton(getDeadbandedOperatorController(), XboxController.LEFT_BUMPER_BUTTON) + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.LEFT_BUMPER_BUTTON) .onTrue(new InstantCommand(() -> m_robotShooter.spin(0.5), m_robotShooter)) .onFalse(turnOffShoot); - new JoystickButton(getDeadbandedOperatorController(), XboxController.RIGHT_BUMPER_BUTTON) + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_BUMPER_BUTTON) .onTrue(i) - .onFalse(new InstantCommand(() -> m_robotIntake.talonPIDIn())); + .onFalse(new InstantCommand(() -> m_robotIntake.PIDIn())); //spins up shooter, no wind down - new JoystickButton(getDeadbandedOperatorController(), XboxController.LEFT_JOYSTICK_BUTTON) + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.LEFT_JOYSTICK_BUTTON) .onTrue(new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter)); - // new JoystickButton(getDeadbandedOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) + // DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) // .onTrue(new InstantCommand(() -> m_robotIntake.talonSpinIntakeMotor(), m_robotIntake)) // .onFalse(new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake)); - new JoystickButton(getDeadbandedOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) .onTrue(emergencyRetract); new Trigger(() -> getDeadbandedOperatorController().getRawAxis(XboxController.RIGHT_TRIGGER_AXIS) > 0.5) @@ -490,156 +369,36 @@ public class RobotContainer { .onTrue(new InstantCommand(() -> m_robotIntake.ampOuttake(0.5))); } + + /** + * This method is used to replcate {@link Trigger Triggers} for {@link VirtualController Virtual Controllers}. + * Please use {@link RobotContainer#DualJoystickButton} for standard buttons. + */ + private void configureVirtualButtonBindings() { - private void configureVirtualButtonBindings() { - // ? /* Driver Buttons */ - - new JoystickButton(getVirtualDriverController(), XboxController.A_BUTTON) - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive)); - - new JoystickButton(getVirtualDriverController(), XboxController.BACK_BUTTON) - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightBlue())) - .onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180())); - - new JoystickButton(getVirtualDriverController(), XboxController.START_BUTTON) - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp())) - .onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180())); - - - // * /* D-Pad Stuff */ - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > 0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 1), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); - - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.TOP_BOTTOM_DPAD_AXIS) > -0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, -1), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); - - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.LEFT_RIGHT_DPAD_AXIS) > 0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(1, 0), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); - - // new Trigger(() -> getVirtualDriverController().getRawAxis(XboxController.LEFT_RIGHT_DPAD_AXIS) > -0.9) - // .onTrue(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(-1, 0), - // new Translation2d(0, 0), - // true))) - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.driveWithInput(new Translation2d(0, 0), - // new Translation2d(0, 0), - // true))); - // ! /* Auto Recording */ - new JoystickButton(m_autoRecorderXbox, XboxController.LEFT_BUMPER_BUTTON) - .whileTrue(new neoJoystickRecorder(m_robotSwerveDrive, - new DeadbandedXboxController[]{getDeadbandedDriverController(), getDeadbandedOperatorController()}, - () -> autoplaybackName.get())) - .onFalse(new InstantCommand()); - - new JoystickButton(m_autoRecorderXbox, XboxController.RIGHT_BUMPER_BUTTON) - .onTrue(new neoJoystickPlayback(m_robotSwerveDrive, - () -> autoplaybackName.get(), - new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, - true, false)) - .onFalse(new InstantCommand()); + /* Notice: the following buttons have not been replicated + * Swerve Drive Slow and Fast mode Gear Shifts : Fast mode is known to cause drift, so we disable that feature in Autoplayback + * Swerve Drive Rotation Gear Shifts : Same reason as Slow and Fast mode. + * Auto Recording controls : We don't want an Null Ouroboros for an auto. + */ - // new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) - // .whileTrue(new JoystickRecorder(m_robotSwerveDrive, - // () -> getDeadbandedDriverController().getLeftX(), - // () -> getDeadbandedDriverController().getLeftY(), - // () -> getDeadbandedDriverController().getRightX(), - // () -> getDeadbandedDriverController().getRightY(), - // "Taxi.txt")) - // .onFalse(new InstantCommand()); + // ? /* Operator Buttons */ - // new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) - // .onTrue(new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt")) - // .onFalse(new InstantCommand()); - // ! /* Speed */ - new JoystickButton(getVirtualDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp())); - // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.setToFast())); - - new JoystickButton(getVirtualDriverController(), XboxController.LEFT_BUMPER_BUTTON) // final - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDown())); + /* Notice: the following buttons have not been replicated + * Override Intake Position Encoder : It's an emergancy overide, for when the position of intake when the robot boots, the intake is not inside the robot. + * We don't need it in an auto. + * Climbing controls : We don't need to climb in auto. + */ - new Trigger(() -> getVirtualDriverController().getPOV() == 270) - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDownRot())); + // new Trigger(() -> getVirtualOperatorController().getRawAxis(XboxController.RIGHT_TRIGGER_AXIS) > 0.5) + // .onTrue(new InstantCommand(() -> m_robotClimber.climbOut())) + // .onFalse(new InstantCommand(() -> m_robotClimber.stopClimb())); - new Trigger(() -> getVirtualDriverController().getPOV() == 90) - .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot())); - - // new JoystickButton(getVirtualDriverController(), XboxController.Y_BUTTON) - // .whileTrue(new InstantCommand(() -> - // m_robotSwerveDrive.driveWithInput(new Translation2d(0, 1), - // new Translation2d(0, 0), - // true), m_robotSwerveDrive)); - - - //? /* Operator Buttons */ - - new JoystickButton(getVirtualOperatorController(), XboxController.Y_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonPIDIn())) - .onFalse(new InstantCommand(() -> m_robotIntake.talonStopArmMotor())); - - new JoystickButton(getVirtualOperatorController(), XboxController.X_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonPIDOut())) - .onFalse(new InstantCommand(() -> m_robotIntake.talonStopArmMotor())); - - new JoystickButton(getVirtualOperatorController(), XboxController.A_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonHandoff())) - .onFalse(new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors())); - - new JoystickButton(getVirtualOperatorController(), XboxController.B_BUTTON) - .onTrue(emergencyRetract); - - - // Override Intake Position encoder: out - new JoystickButton(getVirtualOperatorController(), XboxController.BACK_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonSetPivotEncoderPosition(-55), m_robotIntake)); - - // Override Intake Position encoder: in - new JoystickButton(getVirtualOperatorController(), XboxController.START_BUTTON) - .onTrue(new InstantCommand(() -> m_robotIntake.talonSetPivotEncoderPosition(-6.2), m_robotIntake)); - - new JoystickButton(getVirtualOperatorController(), XboxController.LEFT_BUMPER_BUTTON) - .onTrue(new InstantCommand(() -> m_robotShooter.spin(0.5), m_robotShooter)) - .onFalse(turnOffShoot); - - - new JoystickButton(getVirtualOperatorController(), XboxController.RIGHT_BUMPER_BUTTON) - .onTrue(i) - .onFalse(new InstantCommand(() -> m_robotIntake.talonPIDIn())); - - //spins up shooter, no wind down - new JoystickButton(getVirtualOperatorController(), XboxController.LEFT_JOYSTICK_BUTTON) - .onTrue(new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter)); - - // new JoystickButton(getDeadbandedOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) - // .onTrue(new InstantCommand(() -> m_robotIntake.talonSpinIntakeMotor(), m_robotIntake)) - // .onFalse(new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake)); - - new JoystickButton(getVirtualOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) - .onTrue(emergencyRetract); - - new Trigger(() -> getVirtualOperatorController().getRawAxis(XboxController.RIGHT_TRIGGER_AXIS) > 0.5) - .onTrue(new InstantCommand(() -> m_robotClimber.climbOut())) - .onFalse(new InstantCommand(() -> m_robotClimber.stopClimb())); - - new Trigger(() -> getVirtualOperatorController().getRawAxis(XboxController.LEFT_TRIGGER_AXIS) > 0.5) - .onTrue(new InstantCommand(() -> m_robotClimber.climbIn())) - .onFalse(new InstantCommand(() -> m_robotClimber.stopClimb())); + // new Trigger(() -> getVirtualOperatorController().getRawAxis(XboxController.LEFT_TRIGGER_AXIS) > 0.5) + // .onTrue(new InstantCommand(() -> m_robotClimber.climbIn())) + // .onFalse(new InstantCommand(() -> m_robotClimber.stopClimb())); new Trigger(() -> getVirtualOperatorController().getPOV() == 0) .onTrue(new InstantCommand(() -> m_robotIntake.ampOuttake(0.5))); @@ -657,6 +416,16 @@ public class RobotContainer { //return playbackChooser.getCommand(); } + /** + * A button binding for two controllers, preferably an {@link DeadbandedXboxController Xbox Controller} and {@link VirtualController Virtual Xbox Controller} + * @param joystickA A controller + * @param joystickB A controller + * @param buttonNumber The button to bind to + */ + public Trigger DualJoystickButton(GenericHID joystickA, GenericHID joystickB, int buttonNumber) { + return new Trigger(() -> (joystickA.getRawButton(buttonNumber) || joystickB.getRawButton(buttonNumber))); + } + /** * Add your docs here. */ diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index ef03f99..512b84c 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -13,12 +13,8 @@ import com.ctre.phoenix.sensors.CANCoder; import com.ctre.phoenix.sensors.WPI_Pigeon2; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.hardware.TalonFX; -import com.revrobotics.CANSparkLowLevel; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkMaxLowLevel.MotorType; import edu.wpi.first.wpilibj.motorcontrol.Spark; -import edu.wpi.first.wpilibj.motorcontrol.Talon; import frc4388.robot.Constants.LEDConstants; import frc4388.robot.Constants.SwerveDriveConstants; import frc4388.robot.Constants.ShooterConstants; diff --git a/src/main/java/frc4388/robot/commands/Autos/ArmIntakeInTimeout.java b/src/main/java/frc4388/robot/commands/Autos/ArmIntakeInTimeout.java index 1e1e523..5a40e2a 100644 --- a/src/main/java/frc4388/robot/commands/Autos/ArmIntakeInTimeout.java +++ b/src/main/java/frc4388/robot/commands/Autos/ArmIntakeInTimeout.java @@ -29,23 +29,23 @@ public class ArmIntakeInTimeout extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - robotIntake.talonPIDOut(); - robotIntake.talonSpinIntakeMotor(); + robotIntake.PIDOut(); + robotIntake.spinIntakeMotor(); } // Called once the command ends or is interrupted. @Override public void end(boolean interrupted) { if(interrupted) { - robotIntake.talonPIDIn(); - robotIntake.talonStopIntakeMotors(); + robotIntake.PIDIn(); + robotIntake.stopIntakeMotors(); } } // Returns true when the command should end. @Override public boolean isFinished() { - return robotIntake.getTalonIntakeLimitSwitchState(); + return robotIntake.getIntakeLimitSwitchState(); // if(!(!robotIntake.getTalonIntakeLimitSwitchState() != !false) && ((-1.0 / 0.0) == (-2.0 / 0.0))) // { // return !true==true; diff --git a/src/main/java/frc4388/robot/commands/Autos/AutoBalance.java b/src/main/java/frc4388/robot/commands/Autos/AutoBalance.java index 312325e..9b46468 100644 --- a/src/main/java/frc4388/robot/commands/Autos/AutoBalance.java +++ b/src/main/java/frc4388/robot/commands/Autos/AutoBalance.java @@ -43,7 +43,7 @@ public class AutoBalance extends PID { public void runWithOutput(double output) { double out2 = MathUtil.clamp(output / 40, -59, 0); if (Math.abs(getError()) < 3) out2 = 0; - intake.talonPIDPosition(out2); + intake.PIDPosition(out2); } } diff --git a/src/main/java/frc4388/robot/commands/Intake/ArmIntakeIn.java b/src/main/java/frc4388/robot/commands/Intake/ArmIntakeIn.java index 78c558b..42f9dfc 100644 --- a/src/main/java/frc4388/robot/commands/Intake/ArmIntakeIn.java +++ b/src/main/java/frc4388/robot/commands/Intake/ArmIntakeIn.java @@ -29,8 +29,8 @@ public class ArmIntakeIn extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - robotIntake.talonPIDOut(); - robotIntake.talonSpinIntakeMotor(); + robotIntake.PIDOut(); + robotIntake.spinIntakeMotor(); } // Called once the command ends or is interrupted. @@ -40,7 +40,7 @@ public class ArmIntakeIn extends Command { // Returns true when the command should end. @Override public boolean isFinished() { - return robotIntake.getTalonIntakeLimitSwitchState(); + return robotIntake.getIntakeLimitSwitchState(); // if(!(!robotIntake.getTalonIntakeLimitSwitchState() != !false) && ((-1.0 / 0.0) == (-2.0 / 0.0))) // { // return !true==true; diff --git a/src/main/java/frc4388/robot/subsystems/Intake.java b/src/main/java/frc4388/robot/subsystems/Intake.java index abd12fc..7d7294c 100644 --- a/src/main/java/frc4388/robot/subsystems/Intake.java +++ b/src/main/java/frc4388/robot/subsystems/Intake.java @@ -4,116 +4,30 @@ package frc4388.robot.subsystems; -import java.util.function.BooleanSupplier; - -import com.ctre.phoenix.motorcontrol.ControlMode; -import com.ctre.phoenix.motorcontrol.LimitSwitchNormal; -import com.ctre.phoenix.motorcontrol.can.TalonSRXPIDSetConfiguration; -import com.ctre.phoenix6.configs.HardwareLimitSwitchConfigs; import com.ctre.phoenix6.configs.Slot0Configs; import com.ctre.phoenix6.configs.TalonFXConfiguration; import com.ctre.phoenix6.controls.PositionVoltage; -import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.hardware.TalonFX; -import com.ctre.phoenix6.signals.ForwardLimitTypeValue; -import com.ctre.phoenix6.signals.ForwardLimitValue; import com.ctre.phoenix6.signals.NeutralModeValue; -import com.ctre.phoenix6.signals.ReverseLimitTypeValue; -import com.ctre.phoenix6.signals.ReverseLimitValue; -import com.revrobotics.CANSparkBase; -import com.revrobotics.CANSparkMax; -import com.revrobotics.SparkLimitSwitch; -import com.revrobotics.SparkPIDController; -import com.revrobotics.RelativeEncoder; -import edu.wpi.first.wpilibj.CAN; -import edu.wpi.first.wpilibj.motorcontrol.Spark; -import edu.wpi.first.wpilibj.motorcontrol.Talon; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc4388.robot.Constants; import frc4388.robot.Constants.IntakeConstants; -import frc4388.robot.commands.PID; import frc4388.utility.Gains; -import frc4388.utility.configurable.ConfigurableDouble; public class Intake extends SubsystemBase { - - //NEO - private CANSparkMax intakeMotor; - private CANSparkMax pivot; - private SparkPIDController m_spedController; - private SparkLimitSwitch forwardLimit; - private SparkLimitSwitch reverseLimit; - private SparkLimitSwitch intakeforwardLimit; - private SparkLimitSwitch intakereverseLimit; - - //Talon - private TalonFX talonIntake; - private TalonFX talonPivot; - private CANcoder encoder; - - private boolean r; - - private HardwareLimitSwitchConfigs l; - - TalonFXConfiguration doodooController = new TalonFXConfiguration(); - + private TalonFX intakeMotor; + private TalonFX pivotMotor; public static Gains armGains = IntakeConstants.ArmPID.INTAKE_GAINS; - private ConfigurableDouble outtakeSpeed = new ConfigurableDouble("Outtake Speed", IntakeConstants.INTAKE_OUT_SPEED_UNPRESSED); - private BooleanSupplier sup = () -> true; - private BooleanSupplier dup = () -> false; - - private double smartDashboardOuttakeValue; /** Creates a new Intake. */ - //For NEO - // public Intake(CANSparkMax intakeMotor, CANSparkMax pivot) { - // this.intakeMotor = intakeMotor; - // this.pivot = pivot; + public Intake(TalonFX intakeMotor, TalonFX pivotMotor) { + this.intakeMotor = intakeMotor; + this.pivotMotor = pivotMotor; - // pivot.restoreFactoryDefaults(); - // //pivot.setInverted(true); + intakeMotor.getConfigurator().apply(new TalonFXConfiguration()); + pivotMotor.getConfigurator().apply(new TalonFXConfiguration()); - // forwardLimit = pivot.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); - // reverseLimit = pivot.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); - // forwardLimit.enableLimitSwitch(true); - // reverseLimit.enableLimitSwitch(true); - - // intakeMotor.restoreFactoryDefaults(); - - // intakeforwardLimit = intakeMotor.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); - // intakereverseLimit = intakeMotor.getReverseLimitSwitch(SparkLimitSwitch.Type.kNormallyOpen); - // intakeforwardLimit.enableLimitSwitch(true); - // intakereverseLimit.enableLimitSwitch(false); - - // //Arm PID - // m_spedController = pivot.getPIDController(); - // m_spedController.setP(armGains.kP); - // m_spedController.setI(armGains.kI); - // m_spedController.setD(armGains.kD); - - // SmartDashboard.putNumber("Outtake Speed", IntakeConstants.INTAKE_OUT_SPEED_UNPRESSED); - // } - - //For Talon - public Intake(TalonFX talonIntake, TalonFX talonPivot) { - this.talonIntake = talonIntake; - this.talonPivot = talonPivot; - - talonIntake.getConfigurator().apply(new TalonFXConfiguration()); - talonPivot.getConfigurator().apply(new TalonFXConfiguration()); - - talonIntake.setNeutralMode(NeutralModeValue.Brake); - talonPivot.setNeutralMode(NeutralModeValue.Brake); - - // talonPivot.getConfigurator().apply(new HardwareLimitSwitchConfigs()); - // talonIntake.getConfigurator().apply(new HardwareLimitSwitchConfigs()); - - - - // doodooController.Slot0.kP = armGains.kP; - // doodooController.Slot1.kI = armGains.kI; - // doodooController.Slot2.kD = armGains.kD; + intakeMotor.setNeutralMode(NeutralModeValue.Brake); + pivotMotor.setNeutralMode(NeutralModeValue.Brake); // in init function, set slot 0 gains var slot0Configs = new Slot0Configs(); @@ -121,222 +35,76 @@ public class Intake extends SubsystemBase { slot0Configs.kI = 0.0; // no output for integrated error slot0Configs.kD = 0.21; // A velocity of 1 rps results in 0.1 V output - talonPivot.getConfigurator().apply(slot0Configs); - - + pivotMotor.getConfigurator().apply(slot0Configs); } // ! Talon Methods - public void talonPIDIn() { - PositionVoltage request = new PositionVoltage(-53); - talonPivot.setControl(request.withPosition(0)); + public void PIDIn() { + PIDPosition(0); } - public void talonPIDOut() { - PositionVoltage request = new PositionVoltage(0); - talonPivot.setControl(request.withPosition(-53)); + public void PIDOut() { + PIDPosition(-53); } - public void talonPIDPosition(double out2) { - PositionVoltage request = new PositionVoltage(out2); - talonPivot.setControl(request); + public void PIDPosition(double pos) { + PositionVoltage request = new PositionVoltage(pos); + pivotMotor.setControl(request); } - public void talonHandoff() { - talonIntake.set(-outtakeSpeed.get()); + public void handoff() { + intakeMotor.set(-IntakeConstants.INTAKE_OUT_SPEED_UNPRESSED); } - public void talonSpinIntakeMotor() { - talonIntake.set(IntakeConstants.INTAKE_SPEED); + public void spinIntakeMotor() { + intakeMotor.set(IntakeConstants.INTAKE_SPEED); } - public void talonSpinIntakeMotor(double speed) { - talonIntake.set(speed); + public void spinIntakeMotor(double speed) { + intakeMotor.set(speed); } - public boolean getTalonIntakeLimitSwitchState() { - if(r = talonIntake.getForwardLimit().getValue().value == 0) { - return true; - } - return false; + public boolean getIntakeLimitSwitchState() { + return intakeMotor.getForwardLimit().getValue().value == 0; } - public void talonSetPivotEncoderPosition(double val) { - talonPivot.setPosition(val); + public void setPivotEncoderPosition(double val) { + pivotMotor.setPosition(val); } - public void talonStopIntakeMotors() { - talonIntake.set(0); + public void stopIntakeMotors() { + intakeMotor.set(0); } - public void talonStopArmMotor() { - talonPivot.set(0); + public void stopArmMotor() { + pivotMotor.set(0); + } + + public void stop() { + intakeMotor.set(0); + pivotMotor.set(0); } public double getArmPos() { - return talonPivot.getPosition().getValue(); + return pivotMotor.getPosition().getValue(); } public void resetArmPosition() { - if(getTalonIntakeLimitSwitchState()){ + if (getIntakeLimitSwitchState()) { // talonPivot.setPosition(0); } } public void ampPosition() { - PositionVoltage request = new PositionVoltage(-0); - talonPivot.setControl(request.withPosition(-59)); //TODO: Find actual value + PIDPosition(-59); //TODO: Find actual value } public void ampOuttake(double speed) { - talonSpinIntakeMotor(speed); + spinIntakeMotor(speed); } - - // ! NEO Methods - //hanoff - // public void spinIntakeMotor() { - // intakeMotor.set(IntakeConstants.INTAKE_SPEED); - // } - - // //Rotate robot in for handoff - // public void rotateArmIn() { - // pivot.set(IntakeConstants.PIVOT_SPEED); - // } - - // //Rotates robot out for intake - // public void rotateArmOut() { - // pivot.set(-IntakeConstants.PIVOT_SPEED); - - // } - - // public void pidIn() { - // m_spedController.setReference(2.5, CANSparkMax.ControlType.kPosition); - // //SmartDashboard.putNumber("Velocity Output", pivot.getEncoder().getVelocity()); - // } - - // public void pidOut() { - // m_spedController.setReference(-53, CANSparkMax.ControlType.kPosition); - // } - - // public void limitNote() { - // if (intakeforwardLimit.isPressed()) { - // rotateArmIn2(); - // } else { - // spinIntakeMotor(); - // } - // } - - // public void rotateArmOut2() { - // if(reverseLimit.isPressed()){ - // stopArmMotor(); - // } else { - // pidOut(); - // } - // } - - // public void rotateArmIn2() { - // if(forwardLimit.isPressed()){ - // stopArmMotor(); - // } else { - // pidIn(); - // } - // } - - // public void handoff() { - // intakeMotor.set(-IntakeConstants.INTAKE_OUT_SPEED_UNPRESSED); - // } - - // public void handoff2() { - // if(intakeforwardLimit.isPressed()) { - // intakeMotor.set(-smartDashboardOuttakeValue); - // } else { - // intakeMotor.set(-smartDashboardOuttakeValue); - // } - // } - - // public void stopIntakeMotors() { - // intakeMotor.set(0); - // } - - // public void stopArmMotor() { - // pivot.set(0); - // } - - // public RelativeEncoder getEncoder() { - // return pivot.getEncoder(); - // } - - // public boolean getForwardLimitSwitchState() { - // return forwardLimit.isPressed(); - // } - - // public boolean getReverseLimitSwitchState() { - // return reverseLimit.isPressed(); - // } - - // public boolean getIntakeLimitSwtichState() { - // return intakeforwardLimit.isPressed(); - // } - - // public void setVoltage(double voltage) { - // pivot.setVoltage(voltage); - // } - - // public double getVelocity() { - // return pivot.getEncoder().getVelocity(); - // } - - // public void setPivotEncoderPosition(int val) { - // pivot.getEncoder().setPosition(val); - // } - - // public void resetPosition() { - // if(forwardLimit.isPressed()) { - // setPivotEncoderPosition(0); - // } - // } - - // public double getPos() { - // return pivot.getEncoder().getPosition(); - // } - - // public double getIntakeVelocity() { - // return intakeMotor.getEncoder().getVelocity(); - // } - - // public void rotateArm() { - - // } - - // public BooleanSupplier getArmFowardLimitState() { - // if(forwardLimit.isPressed()) { - // return sup; - // } else { - // return dup; - // } - // } - - // public void changeIntakeNeutralState() { - // if(forwardLimit.isPressed()) { - // intakeMotor.setIdleMode(CANSparkBase.IdleMode.kCoast); - // } - // } - @Override public void periodic() { - // This method will be called once per scheduler run - // SmartDashboard.putNumber("Vel Output", getVelocity()); - // SmartDashboard.putNumber("Position", getPos()); - // resetPosition(); - // changeIntakeNeutralState(); - resetArmPosition(); - - // SmartDashboard.putNumber("Pivot Position", getArmPos()); - - //smartDashboardOuttakeValue = SmartDashboard.getNumber("Outtake Speed", IntakeConstants.INTAKE_OUT_SPEED_UNPRESSED); - - //SmartDashboard.putBoolean("Limit Switch State", getTalonIntakeLimitSwitchState()); } } diff --git a/src/main/java/frc4388/utility/DualJoystickButton.java b/src/main/java/frc4388/utility/DualJoystickButton.java new file mode 100644 index 0000000..e4ef5ed --- /dev/null +++ b/src/main/java/frc4388/utility/DualJoystickButton.java @@ -0,0 +1,22 @@ +package frc4388.utility; + +import edu.wpi.first.wpilibj.GenericHID; +import edu.wpi.first.wpilibj2.command.button.Trigger; + + +/** + * A button binding for two controllers, preferably an {@link frc4388.utility.controller.DeadbandedXboxController Xbox Controller} and {@link frc4388.utility.controller.VirtualController Virtual Xbox Controller} + * @author Zachary Wilke + */ +public class DualJoystickButton extends Trigger { + + /** + * Creates an Button binding on two controllers + * @param joystickA A controller + * @param joystickB A controller + * @param buttonNumber The button to bind to + */ + public DualJoystickButton(GenericHID joystickA, GenericHID joystickB, int buttonNumber) { + super(() -> (joystickA.getRawButton(buttonNumber) || joystickB.getRawButton(buttonNumber))); + } +} From 6d5655356502782fc0ec43c3fe11c8f9e78d890c Mon Sep 17 00:00:00 2001 From: C4llSqin <83995467+C4llSqin@users.noreply.github.com> Date: Tue, 7 May 2024 16:38:30 -0600 Subject: [PATCH 2/4] patches --- .github/workflows/gradle.yml | 4 ++-- autos/final_1note_stationary.auto | Bin 0 -> 11345 bytes autos/final_red_center_4note_taxi.auto | Bin 0 -> 76469 bytes .../utility/controller/VirtualController.java | 2 +- 4 files changed, 3 insertions(+), 3 deletions(-) create mode 100644 autos/final_1note_stationary.auto create mode 100644 autos/final_red_center_4note_taxi.auto diff --git a/.github/workflows/gradle.yml b/.github/workflows/gradle.yml index 9eaf0d0..7d89e58 100644 --- a/.github/workflows/gradle.yml +++ b/.github/workflows/gradle.yml @@ -13,10 +13,10 @@ jobs: runs-on: ubuntu-latest steps: - uses: actions/checkout@v1 - - name: Set up JDK 1.8 + - name: Set up JDK 17 uses: actions/setup-java@v1 with: - java-version: 1.12 + java-version: 17 - name: Change wrapper permissions run: chmod +x ./gradlew - name: Build with Gradle diff --git a/autos/final_1note_stationary.auto b/autos/final_1note_stationary.auto new file mode 100644 index 0000000000000000000000000000000000000000..f83851cdd1bb4f57568177ac80723b4358c8981a GIT binary patch literal 11345 zcmd6sPl(K69EWFiW@ly(YB|tGxk!p~k(9$;&;Tfgk>Q=fUB_xsLo-=_E1YfrR}w*KqC(P(yl+rh=9 zHO|g$+A~yZ9gUW1ZB<1ncC80Sh1j)S;ZcfR$AD2Ga7~ZDubT>wQtWyPj0&;qmBOPG zyFLJ;LhSmg@F>NupTMY)y4rn(M=5sA0HZ?e+N|&>#jahzs1UnODm+TD>pUkcp~#IDB*k5cS<35*J{>%GFG6uZ6vqeATZrSK@FuFe1$ z6=K&qg-0oN?FB}K*wx^9*g2y{K`EZ=GB7H{u3HL^QtWE*JnTHjl2wT3dZ+Lx#jXa= z!_E&ZS%q}2Zdc(^id}1fQ6Y9+PyD`-bK-yn|f z6T5DcV^ZvTXz1+3t{3E(6uatv+mtriKljI^ zU=PRd5PQv>hbykrW)gPdxvr99QtTQUIy-@@wfx(rH%E?1vFo*=vlF}O?!N5**LV;6 zQ(Uu2>0JG~JEF3=nmG?w_Hc*UHFn}XJVcI3vFnJTvlF{ckz-Qqx@hR^#I76Um=wG2 z89F<$Yn~jFVprWgTiLns(M-ZlI@e$oIVQ!f4TjE6?Al6>NwMpIp|caaPLN|#?5exd qD|+S!*UTjB#B<#x$E4Wx$k5q|T@9X5gSvN!MbE}m-8;lG*UVpBF_YW? literal 0 HcmV?d00001 diff --git a/autos/final_red_center_4note_taxi.auto b/autos/final_red_center_4note_taxi.auto new file mode 100644 index 0000000000000000000000000000000000000000..b20ab8403b4d97fd6083b9c3b6e3e2d554f754de GIT binary patch literal 76469 zcmd7bd6X2z9S87TaX|#R6y*>EMC6uB6oJ$}-6Y<4##`|W;fX;EL==~;^(dJ1SQ2U;6}RwKkxZPZUVt66KH z)fs5@1zLvzt)qa}X+R5e&E~$on!N+eYaP(q2DEmPB~~0hIZZPKOU6At_jv8zioyac zea$8|UGjE0!39fpUi~Pn*iyGPVQZweYQET!ixH&uK`LXYb)`#w`3O3`j57f--i$Q*41C6 zX{KPwJ~tLnSW%z2^#;&d4Yd4rKKXt4EiSL-ErFJQJ)ihKY(4;(m){;HpVzIxyygL| zCw=RsDQTK1SaRFL=Ibe}s88Jb+P9Ma?9f6#Pf7kdszn!_SK`;$E&R{s$y*bEdEKt9 z#INUDG`ZeL{5lR>M^MKZaKuhp2Q6lehFUL^ACqJ1>15WjAOIuGP8)MTlOqtxnMmT9a*!r3leW zwlyxgL2I(D@f0C?$+oVDZqS-+>uQP+y<}Unq8qd(+nPfWqL*yzq38y!$*|n-A+~;= zB1A9Q){^K3t;x2&qX^MUuCW4+TYtUa~DrJFoWPxzY2X zHQ9M#+If}NwY0U-OLkuR^D@A?C%Qpvvh&ipcxEaSPE<{JzdRT=Td#YE(?Yg21!!F_K7Qt+RCfEf zs{Cl{sT3bMH0hP>yk?8_BQH;9qJ;IG6CXRCK?U1dF4n8QfBN{qldhoeAZ4YaD$h54Bbm1^#j0 zzdD>J(v@#GnP_6`R9>{y$(#UT@5?cs8}9+FTAbCf8PM7XXdQ?< z4?7Ok*P>OmtIN%kE>8`&J?uD%#-|XQdLNyzHA6qIta$FSRGuu%Dt2DC0ua3*@v4d-{^ZG=3-vE=wJ+7cZ^K9#9oV9No*^qKKSf(A?a7)R}Yu{e< z9W%MvLg>Y8>vZ38bhN?~Y-@^dr3w>zDcib9TU9!kWrA%z>RXP*pv7!!skXLIEL+L8 zDzp{3mnz%(250TpQd`xweMif=dF}UGnZ(Kmj$2cu&p`rvr;#*tZ4!?nUu>_UoF3iZ9OU*Q*Ibpqe?%f znv(AZ$LMBTi-6X0+32_l$l6ksNZ_x0Z_M=EDt2D$w6!h7^7>u+9^2X}8ua{UQa_m{Q}To0XC?MNyg*y^O@Jnoa`i(emN%Ja zUC+DU%kDG@Xw8rfrS4YCdM9V=X-0nd$SLJCMy?)JpJv*u~gW@LPMy+pBPg+r4$rHt=*8Q-eOfig2OS|Ohpd@(+&OJ_f7{;3$PzWD{e zHb%?(yMZxUWqt-fa)No@8#ft%ki1&$mT3m$R)&W-MC`+XA-pUH@*&!d%YI>kc!Pt%hyQ zw?#IWv#saMShgCrwZs5shHYJJi)=1uTUVN~Y&C4_Z??$ha<=tvGnTD}ZQW~&Y%XV8nD$V$Q9I1-w$*U+ z>Q-WlY%XV89nDy_8n)Hj7TH|Rwt#JKw^DPvZ8hw?#@Qm9%h?ui?7nV)Ft^)Q!^q1W z$E+LXTGYKq+-KUC4gf?%HzQ&BZ+s~Tv1P0ysn!u;a{nAvgj>Rv3p z{$2p9HPGrx&kzB5^^;yd0P%A0xruqCcI`auUPjNCh0(uDMULejto!=vekMIP7sh>E z&w4|R(dB2!I1hVd|4;YdTdg?yeJSf2y$=`nDs%je*Hf|dF;iBi?|}*{j6PSYUM`KH z?}4(G$Ze%=P+{~x@vJ!dvngw%etjAJPh!lg$UQe2q}R7h7=1$Gwhk!KmeD69cB`|j zRWWHyI5p@0m2n&|cOM?mUt4Q~{S3Xl;^6U0dFGFbP^6fmUyzH5_P_$!fwTcL321$Rvw9W*t+qg`yZ>5F`aJA81ZW+l z_hDL%UG2Wun*5Qmy}o*$BdZ)Ya`N9_?m1Idm3r2e<>l^_?GNMgvfFO-oFg}<+~A@r z>3d&2UjkZ7Wo4<#YisbkS8jElKkR*2AwPALRh@sFKoetIwQ_@sCTgc_NtuE3)Ud5@ zsZXjf`X}dM+$yfst0mCdSAMLvUl@IBW6$d#pfy%{W1|D|Iss@+1zI-&t-FENi`p{! zuE&1PF9lj_d@KKb05dyw8?^;!eW$IuX$@&Ji99vjybjz`TlH6ek+9VTX!Vop)ov2? zYP{P#J1tPf-iM>)MwoT9wrca=(+eb(nPum7ouuoHkTG>*v~D(I*=pE%y=;qYE@xY- z%viP>ww1O;HkY%lMl+VJhHEjpz_8Ex-fbxh`8G}2N_Jj7C^Ep(zsm`*E(PW_1!&zs z_d~5O8SkA7|x9cf!4F4QT+}AJqOE4Dl-#fUQ2-12cq%EAF{as^4g@2m-nnb z!F{*`XZ6{`w^G5B-1+#2}4zTXi?R?0&k&~o5!#-XM=)MN^p)+F#YuMJC z+Vc9)1tXjDY^xGzZO2&$7Xz)~K&w>Lt1%*}&!c%R1Z%kG#=)o3vkibXUSDG;e$F2} zS$NM56V1#04*0>>3vV2yu!W7}=a> zTg!ykk6eD}m|^qQur2RtW!|76m29gfBw&GRw)ItkpdpL6R^Oo^0Si>Kt)mJA4Ozst zfa5vzJvU_I3skf7()aWV1P?4?Tk`^eBFwTaeTO6h;;q8Ao{w(Onrv$cMTlOqt<}*D zT9a)xP=x3u*XjoxOQ+x9==so^?7WVo2+>Qnb#ior)?{1bDMIv;ZB34D(3))PpA;c_ z$*|n<0s7q+-Jmtu)-x0#ddaq4i*C@GZ0jA05WVDD{i73lO}5oehlo7Ewz@|q^onc? z)AqWrul|^}S6Soqu8BOs-iK#LCiIGI3p2)o+J~5N9hC(f-=@EQf~F6Lb%K4op0$QH zR$yBzj8N7JhUJdG(SN5kw6Ox$8h{yF%m${IkS>37>`KD=aGV=1Pn z3jPKGEeV!v>llh867MfMK;H)tpOb1U*?H;j0|KnurK9oySmm-DW<3M6s({v4IBQ@D z(CPrRdIGJXKx+)pI!1cWsFQCu2A(BnquPyu(}312pmi6}dI)C?Dh67efYv~uH411Q z3$)G#TGN5njX>*PKr02bRsyYhptTcc4c-%Ibp~2}f!0`{bso_ABhZ=ww4MT5!1i$P z2f)12K^Qr|}-{7nv zdjPF2K&ubXDg#>MarY{R+$Fv5XeNJObjV}U>sbk~7D?|3Gr(E_wARZ7sC&ypYJt{H zoHg`7pmiwFDx=>-PX3%9Iv;4gAieKT0`giTyE?G5p(qzRmZAR%GJul_SppT9*N>sX%KM(3%UhyeFfO^YA%fUateKl|btgptT)m9X1ANodmQl z1X@=DEl12&zjc@V``2N&i8<=GkO9_Qp!EpQdIe~`1+>=Vti#&^twBI*4A43OXq^YN zCIYSLKx-Dzx&vt45408lt=EB81 Date: Tue, 7 May 2024 16:41:46 -0600 Subject: [PATCH 3/4] Disable camera --- src/main/java/frc4388/robot/RobotContainer.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 3e0325c..570e650 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -178,7 +178,7 @@ public class RobotContainer { DriverStation.silenceJoystickConnectionWarning(true); - CameraServer.startAutomaticCapture(); + // CameraServer.startAutomaticCapture(); /* Default Commands */ // drives the robot with a two-axis input from the driver controller @@ -371,8 +371,8 @@ public class RobotContainer { } /** - * This method is used to replcate {@link Trigger Triggers} for {@link VirtualController Virtual Controllers}. - * Please use {@link RobotContainer#DualJoystickButton} for standard buttons. + * This method is used to replcate {@link Trigger Triggers} for {@link VirtualController Virtual Controllers}.

+ * Please use {@link RobotContainer#DualJoystickButton} in {@link RobotContainer#configureButtonBindings} for standard buttons. */ private void configureVirtualButtonBindings() { From 1d2f77299341ddcc57fbdc468b1ca32ca4b953da Mon Sep 17 00:00:00 2001 From: C4llSqin <83995467+C4llSqin@users.noreply.github.com> Date: Tue, 7 May 2024 17:07:14 -0600 Subject: [PATCH 4/4] finalize cleanup --- .../java/frc4388/robot/RobotContainer.java | 29 +------------------ 1 file changed, 1 insertion(+), 28 deletions(-) diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 570e650..bac8be0 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -204,12 +204,6 @@ public class RobotContainer { } - // private void changeAuto() { - // autoPlayback.unloadAuto(); - // autoPlayback.loadAuto(); - // lastAutoName = autoplaybackName.get(); - // System.out.println("AUTO: Changed auto to; `" + lastAutoName + "`"); - // } /** * Use this method to define your button->command mappings. Buttons can be * created by instantiating a {@link GenericHID} or one of its subclasses @@ -278,18 +272,6 @@ public class RobotContainer { true, false)) .onFalse(new InstantCommand()); - // new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) - // .whileTrue(new JoystickRecorder(m_robotSwerveDrive, - // () -> getDeadbandedDriverController().getLeftX(), - // () -> getDeadbandedDriverController().getLeftY(), - // () -> getDeadbandedDriverController().getRightX(), - // () -> getDeadbandedDriverController().getRightY(), - // "Taxi.txt")) - // .onFalse(new InstantCommand()); - - // new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) - // .onTrue(new JoystickPlayback(m_robotSwerveDrive, "Taxi.txt")) - // .onFalse(new InstantCommand()); // ! /* Speed */ new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp())); @@ -304,12 +286,7 @@ public class RobotContainer { new Trigger(() -> getDeadbandedDriverController().getPOV() == 90) .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot())); - // new JoystickButton(getDeadbandedDriverController(), XboxController.Y_BUTTON) - // .whileTrue(new InstantCommand(() -> - // m_robotSwerveDrive.driveWithInput(new Translation2d(0, 1), - // new Translation2d(0, 0), - // true), m_robotSwerveDrive)); - + //? /* Operator Buttons */ @@ -349,10 +326,6 @@ public class RobotContainer { //spins up shooter, no wind down DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.LEFT_JOYSTICK_BUTTON) .onTrue(new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter)); - - // DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) - // .onTrue(new InstantCommand(() -> m_robotIntake.talonSpinIntakeMotor(), m_robotIntake)) - // .onFalse(new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake)); DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_JOYSTICK_BUTTON) .onTrue(emergencyRetract);