diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 8ccef78..c3287b7 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -32,6 +32,7 @@ import edu.wpi.first.wpilibj2.command.WaitUntilCommand; // Autos import frc4388.robot.commands.Autos.PlaybackChooser; +import frc4388.robot.commands.Intake.ArmIntakeIn; import frc4388.robot.commands.Swerve.JoystickPlayback; import frc4388.robot.commands.Swerve.JoystickRecorder; import frc4388.utility.controller.VirtualController; @@ -39,7 +40,10 @@ import frc4388.robot.commands.Swerve.neoJoystickPlayback; import frc4388.robot.commands.Swerve.neoJoystickRecorder; // import frc4388.robot.commands.Intake.ArmIntakeIn; //import frc4388.robot.commands.Autos.AutoAlign; - +import frc4388.robot.subsystems.Climber; +import frc4388.robot.subsystems.Intake; +import frc4388.robot.subsystems.Limelight; +import frc4388.robot.subsystems.Shooter; // Subsystems // import frc4388.robot.subsystems.LED; // import frc4388.robot.subsystems.Limelight; @@ -66,7 +70,7 @@ public class RobotContainer { /* Subsystems */ // private final LED m_robotLED = new LED(); - // private final Intake m_robotIntake = new Intake(m_robotMap.intakeMotor, m_robotMap.pivotMotor); + 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, @@ -78,27 +82,89 @@ public class RobotContainer { /* 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 DeadbandedXboxController m_autoRecorderXbox = new DeadbandedXboxController(2); + private final Limelight limelight = new Limelight(); + + private final Shooter m_robotShooter = new Shooter(m_robotMap.leftShooter, m_robotMap.rightShooter, limelight); + + private final Climber m_robotClimber = new Climber(m_robotMap.climbMotor); + /* Virtual Controllers */ - // private final VirtualController m_virtualDriver = new VirtualController(0); - // private final VirtualController m_virtualOperator = new VirtualController(1); + private final VirtualController m_virtualDriver = new VirtualController(0); + private final VirtualController m_virtualOperator = new VirtualController(1); - // private Command intakeToShootStuff = new ArmIntakeIn(m_robotIntake, m_robotShooter); - // private Command interrupt = new InstantCommand(() -> {}, m_robotIntake, m_robotShooter); + private Command intakeToShootStuff = new ArmIntakeIn(m_robotIntake, m_robotShooter); + private Command interrupt = new InstantCommand(() -> {}, m_robotIntake, m_robotShooter); - // private SequentialCommandGroup intakeToShoot = new SequentialCommandGroup( - // 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 intakeToShoot = new SequentialCommandGroup( + 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()) + ); // ! Teleop Commands + private SequentialCommandGroup autoShoot = new SequentialCommandGroup( + // MoveToSpeaker, + //autoAlign, + new InstantCommand(() -> m_robotShooter.spin()), + new WaitCommand(3.0), + new InstantCommand(() -> m_robotIntake.handoff(), m_robotIntake), + new WaitCommand(3.0), + new InstantCommand(() -> m_robotShooter.idle()) + // new InstantCommand(() -> autoAlign.reverse()), + // autoAlign.asProxy() + ); - //private AutoAlign autoAlign = new AutoAlign(m_robotSwerveDrive, limelight); + + private SequentialCommandGroup i = new SequentialCommandGroup( + intakeToShootStuff, intakeToShoot, + new InstantCommand(() -> m_robotShooter.idle()) + ); + + private SequentialCommandGroup ejectToShoot = new SequentialCommandGroup( + new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter), + new WaitCommand(0.75), + new InstantCommand(() -> m_robotIntake.handoff(), m_robotIntake) + ); + + private SequentialCommandGroup turnOffShoot = new SequentialCommandGroup( + new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter) + // new InstantCommand(() -> m_robotIntake.talonStopIntakeMotors(), m_robotIntake) + ); + + private SequentialCommandGroup emergencyRetract = new SequentialCommandGroup( + interrupt, + new InstantCommand(() -> m_robotIntake.PIDIn(), m_robotIntake), + new InstantCommand(() -> m_robotIntake.stopIntakeMotors(), m_robotIntake) + ); + + private SequentialCommandGroup ampShoot = new SequentialCommandGroup( + new InstantCommand(() -> m_robotIntake.ampPosition()), + new InstantCommand(() -> m_robotIntake.ampOuttake(0.1)) //TODO: Find Actual Speed + ); + + // ! /* Autos */ + // 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, + () -> autoplaybackName.get(), // lastAutoName + new VirtualController[]{getVirtualDriverController(), getVirtualOperatorController()}, + true, false); + + // 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 SequentialCommandGroup autoShoot = new SequentialCommandGroup( // // MoveToSpeaker, @@ -179,8 +245,170 @@ public class RobotContainer { * passing it to a {@link edu.wpi.first.wpilibj2.command.button.JoystickButton}. */ private void configureButtonBindings() { - new JoystickButton(getDeadbandedDriverController(), XboxController.A_BUTTON) + + // ? /* Driver Buttons */ + + DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.A_BUTTON) .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroFlip(), m_robotSwerveDrive)); + + DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.BACK_BUTTON) + .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightBlue())) + .onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180())); + + DualJoystickButton(getDeadbandedDriverController(), getVirtualDriverController(), XboxController.START_BUTTON) + .onTrue(new InstantCommand(() -> m_robotSwerveDrive.resetGyroRightAmp())) + .onFalse(new InstantCommand(() -> m_robotSwerveDrive.add180())); + + // * /* D-Pad Stuff */ + // new Trigger(() -> getDeadbandedDriverController().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(() -> getDeadbandedDriverController().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(() -> getDeadbandedDriverController().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(() -> getDeadbandedDriverController().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()); + + // ! /* Speed */ + new JoystickButton(getDeadbandedDriverController(), XboxController.RIGHT_BUMPER_BUTTON) // final + .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUp())); + // .onFalse(new InstantCommand(() -> m_robotSwerveDrive.setToFast())); + + new JoystickButton(getDeadbandedDriverController(), XboxController.LEFT_BUMPER_BUTTON) // final + .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDown())); + + new Trigger(() -> getDeadbandedDriverController().getPOV() == 270) + .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftDownRot())); + + new Trigger(() -> getDeadbandedDriverController().getPOV() == 90) + .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot())); + + + + //? /* Operator Buttons */ + + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.Y_BUTTON) + .onTrue(new InstantCommand(() -> m_robotIntake.PIDIn())) + .onFalse(new InstantCommand(() -> m_robotIntake.stopArmMotor())); + + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.X_BUTTON) + .onTrue(new InstantCommand(() -> m_robotIntake.PIDOut())) + .onFalse(new InstantCommand(() -> m_robotIntake.stopArmMotor())); + + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.A_BUTTON) + .onTrue(new InstantCommand(() -> m_robotIntake.handoff())) + .onFalse(new InstantCommand(() -> m_robotIntake.stopIntakeMotors())); + + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.B_BUTTON) + .onTrue(emergencyRetract); + + + // Override Intake Position encoder: out + new JoystickButton(getDeadbandedOperatorController(), XboxController.BACK_BUTTON) + .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.setPivotEncoderPosition(-6.2), m_robotIntake)); + + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.LEFT_BUMPER_BUTTON) + .onTrue(new InstantCommand(() -> m_robotShooter.spin(0.5), m_robotShooter)) + .onFalse(turnOffShoot); + + + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.RIGHT_BUMPER_BUTTON) + .onTrue(i) + .onFalse(new InstantCommand(() -> m_robotIntake.PIDIn())); + + //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(emergencyRetract); + + new Trigger(() -> getDeadbandedOperatorController().getRawAxis(XboxController.RIGHT_TRIGGER_AXIS) > 0.5) + .onTrue(new InstantCommand(() -> m_robotClimber.climbOut())) + .onFalse(new InstantCommand(() -> m_robotClimber.stopClimb())); + + new Trigger(() -> getDeadbandedOperatorController().getRawAxis(XboxController.LEFT_TRIGGER_AXIS) > 0.5) + .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))); + + } + + /** + * 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() { + + // ? /* Driver Buttons */ + + /* 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. + */ + + // ? /* Operator Buttons */ + + /* 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(() -> 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().getPOV() == 0) + .onTrue(new InstantCommand(() -> m_robotIntake.ampOuttake(0.5))); } /** @@ -216,11 +444,11 @@ public class RobotContainer { return this.m_operatorXbox; } - // public VirtualController getVirtualDriverController() { - // return m_virtualDriver; - // } + public VirtualController getVirtualDriverController() { + return m_virtualDriver; + } - // public VirtualController getVirtualOperatorController() { - // return m_virtualOperator; - // } + public VirtualController getVirtualOperatorController() { + return m_virtualOperator; + } } diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 9595f48..d1a2b91 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -71,15 +71,15 @@ public class RobotMap { public final CANcoder rightBackEncoder = new CANcoder(SwerveDriveConstants.IDs.RIGHT_BACK_ENCODER_ID); /* Shooter Subsystem */ - // public final TalonFX leftShooter = new TalonFX(ShooterConstants.LEFT_SHOOTER_ID); - // public final TalonFX rightShooter = new TalonFX(ShooterConstants.RIGHT_SHOOTER_ID); + public final TalonFX leftShooter = new TalonFX(ShooterConstants.LEFT_SHOOTER_ID); + public final TalonFX rightShooter = new TalonFX(ShooterConstants.RIGHT_SHOOTER_ID); /* Intake Subsystem */ - // public final TalonFX intakeMotor = new TalonFX(IntakeConstants.INTAKE_MOTOR_ID); - // public final TalonFX pivotMotor = new TalonFX(IntakeConstants.PIVOT_MOTOR_ID); + public final TalonFX intakeMotor = new TalonFX(IntakeConstants.INTAKE_MOTOR_ID); + public final TalonFX pivotMotor = new TalonFX(IntakeConstants.PIVOT_MOTOR_ID); /* Climber Subsystem */ - // public final TalonFX climbMotor = new TalonFX(ClimbConstants.CLIMB_MOTOR_ID); + public final TalonFX climbMotor = new TalonFX(ClimbConstants.CLIMB_MOTOR_ID); void configureLEDMotorControllers() { } diff --git a/src/main/java/frc4388/robot/commands/Intake/ArmIntakeIn.java b/src/main/java/frc4388/robot/commands/Intake/ArmIntakeIn.java new file mode 100644 index 0000000..42f9dfc --- /dev/null +++ b/src/main/java/frc4388/robot/commands/Intake/ArmIntakeIn.java @@ -0,0 +1,53 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc4388.robot.commands.Intake; + +import edu.wpi.first.wpilibj2.command.Command; +import frc4388.robot.subsystems.Intake; +import frc4388.robot.subsystems.Shooter; +import frc4388.robot.subsystems.SwerveDrive; + +public class ArmIntakeIn extends Command { + /** Creates a new ArmIntakeIn. */ + private Intake robotIntake; + private Shooter robotShooter; + + public ArmIntakeIn(Intake robotIntake, Shooter robotShooter) { + // Use addRequirements() here to declare subsystem dependencies. + this.robotIntake = robotIntake; + this.robotShooter = robotShooter; + + addRequirements(this.robotIntake, this.robotShooter); + } + + // Called when the command is initially scheduled. + @Override + public void initialize() {} + + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + robotIntake.PIDOut(); + robotIntake.spinIntakeMotor(); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) {} + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return robotIntake.getIntakeLimitSwitchState(); + // if(!(!robotIntake.getTalonIntakeLimitSwitchState() != !false) && ((-1.0 / 0.0) == (-2.0 / 0.0))) + // { + // return !true==true; + // } + // else + // { + // return !false==!(!(true)); + // } + } +} diff --git a/src/main/java/frc4388/robot/subsystems/Climber.java b/src/main/java/frc4388/robot/subsystems/Climber.java new file mode 100644 index 0000000..ec78e53 --- /dev/null +++ b/src/main/java/frc4388/robot/subsystems/Climber.java @@ -0,0 +1,62 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc4388.robot.subsystems; + +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.controls.PositionVoltage; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.NeutralModeValue; + +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; + +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc4388.robot.Constants; +import frc4388.robot.Constants.ClimbConstants; +import frc4388.robot.Constants.IntakeConstants; + +//! 6.5C Scoring Criteria for Stage + +public class Climber extends SubsystemBase { + /** Creates a new Climber. */ + TalonFX climbMotor; + + public Climber(TalonFX climbMotor) { + this.climbMotor = climbMotor; + this.climbMotor.setInverted(true); + + climbMotor.setNeutralMode(NeutralModeValue.Brake); + + var slot0Configs = new Slot0Configs(); + slot0Configs.kP = 0.7; // An error of 0.5 rotations results in 12 V output + slot0Configs.kI = 0.0; // no output for integrated error + slot0Configs.kD = 0.06; // A velocity of 1 rps results in 0.1 V output + + climbMotor.getConfigurator().apply(slot0Configs); + } + + public void climbOut() { + //PositionVoltage request = new PositionVoltage(0); + //climbMotor.setControl(request.withPosition(-520)); + + climbMotor.set(Constants.ClimbConstants.CLIMB_OUT_SPEED); + } + + public void climbIn() { + //PositionVoltage request = new PositionVoltage(-520); + //climbMotor.setControl(request.withPosition(0)); + climbMotor.set(Constants.ClimbConstants.CLIMB_IN_SPEED); + ; + } + + public void stopClimb() { + climbMotor.set(0.d); + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + //SmartDashboard.putNumber("climber pos", climbMotor.getPosition().getValue()); + } +} diff --git a/src/main/java/frc4388/robot/subsystems/Intake.java b/src/main/java/frc4388/robot/subsystems/Intake.java new file mode 100644 index 0000000..7d7294c --- /dev/null +++ b/src/main/java/frc4388/robot/subsystems/Intake.java @@ -0,0 +1,110 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc4388.robot.subsystems; + +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.PositionVoltage; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.NeutralModeValue; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc4388.robot.Constants.IntakeConstants; +import frc4388.utility.Gains; + +public class Intake extends SubsystemBase { + private TalonFX intakeMotor; + private TalonFX pivotMotor; + public static Gains armGains = IntakeConstants.ArmPID.INTAKE_GAINS; + + /** Creates a new Intake. */ + public Intake(TalonFX intakeMotor, TalonFX pivotMotor) { + this.intakeMotor = intakeMotor; + this.pivotMotor = pivotMotor; + + intakeMotor.getConfigurator().apply(new TalonFXConfiguration()); + pivotMotor.getConfigurator().apply(new TalonFXConfiguration()); + + intakeMotor.setNeutralMode(NeutralModeValue.Brake); + pivotMotor.setNeutralMode(NeutralModeValue.Brake); + + // in init function, set slot 0 gains + var slot0Configs = new Slot0Configs(); + slot0Configs.kP = 1.3; // An error of 0.5 rotations results in 12 V output + slot0Configs.kI = 0.0; // no output for integrated error + slot0Configs.kD = 0.21; // A velocity of 1 rps results in 0.1 V output + + pivotMotor.getConfigurator().apply(slot0Configs); + } + + // ! Talon Methods + public void PIDIn() { + PIDPosition(0); + } + + public void PIDOut() { + PIDPosition(-53); + } + + public void PIDPosition(double pos) { + PositionVoltage request = new PositionVoltage(pos); + pivotMotor.setControl(request); + } + + public void handoff() { + intakeMotor.set(-IntakeConstants.INTAKE_OUT_SPEED_UNPRESSED); + } + + public void spinIntakeMotor() { + intakeMotor.set(IntakeConstants.INTAKE_SPEED); + } + + public void spinIntakeMotor(double speed) { + intakeMotor.set(speed); + } + + public boolean getIntakeLimitSwitchState() { + return intakeMotor.getForwardLimit().getValue().value == 0; + } + + public void setPivotEncoderPosition(double val) { + pivotMotor.setPosition(val); + } + + public void stopIntakeMotors() { + intakeMotor.set(0); + } + + public void stopArmMotor() { + pivotMotor.set(0); + } + + public void stop() { + intakeMotor.set(0); + pivotMotor.set(0); + } + + public double getArmPos() { + return pivotMotor.getPosition().getValue(); + } + + public void resetArmPosition() { + if (getIntakeLimitSwitchState()) { + // talonPivot.setPosition(0); + } + } + + public void ampPosition() { + PIDPosition(-59); //TODO: Find actual value + } + + public void ampOuttake(double speed) { + spinIntakeMotor(speed); + } + + @Override + public void periodic() { + resetArmPosition(); + } +} diff --git a/src/main/java/frc4388/robot/subsystems/LED.java b/src/main/java/frc4388/robot/subsystems/LED.java index 0d4af80..e9e070c 100644 --- a/src/main/java/frc4388/robot/subsystems/LED.java +++ b/src/main/java/frc4388/robot/subsystems/LED.java @@ -7,6 +7,8 @@ package frc4388.robot.subsystems; +import edu.wpi.first.wpilibj.AddressableLED; +import edu.wpi.first.wpilibj.AddressableLEDBuffer; import edu.wpi.first.wpilibj.motorcontrol.Spark; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -20,44 +22,69 @@ import frc4388.utility.LEDPatterns; */ public class LED extends SubsystemBase { - private LEDPatterns m_currentPattern; - private Spark m_LEDController; - + static AddressableLED m_led; + static AddressableLEDBuffer m_ledBuffer; + static LED m_self; /** * Add your docs here. */ - public LED(Spark LEDController){ - m_LEDController = LEDController; - setPattern(LEDConstants.DEFAULT_PATTERN); - updateLED(); + + public LED(){ + if(m_self != null) + return; + m_led = new AddressableLED(9); + m_ledBuffer = new AddressableLEDBuffer(10); + m_led.setLength(m_ledBuffer.getLength()); + m_led.setData(m_ledBuffer); + m_led.start(); System.err.println("In the Beginning, there was Joe.\nAnd he said, 'Let there be LEDs.'\nAnd it was good."); } - + public static LED getInstance() { + if(m_self == null) + m_self = new LED(); + return m_self; + } @Override public void periodic(){ - SmartDashboard.putNumber("LED", m_currentPattern.getValue()); + //gamermode(); + //SmartDashboard.putNumber("LED", m_currentPattern.getValue()); + return; + } + static int firstcolor = 0; + static void gamermode() { + for(int i = 0; i < m_ledBuffer.getLength(); i++) { + final int hue = (firstcolor + (i * 180 / m_ledBuffer.getLength())) % 180; + setLEDHSV(i, hue, 255, 128); + } + firstcolor +=3; + firstcolor %= 180; + } + /** + * Add your docs here. + */ + public static void updateLED (){ + gamermode(); + // m_LEDController.set(m_currentPattern.getValue()); } /** * Add your docs here. */ - public void updateLED(){ - m_LEDController.set(m_currentPattern.getValue()); + public static void setLEDRGB(int lednum, int r, int g, int b){ + m_ledBuffer.setRGB(lednum, r, g, b); + //m_currentPattern = pattern; + // m_LEDController.set(m_currentPattern.getValue()); } - - /** - * Add your docs here. - */ - public void setPattern(LEDPatterns pattern){ - m_currentPattern = pattern; - m_LEDController.set(m_currentPattern.getValue()); + public static void setLEDHSV(int lednum, int hue, int sat, int val){ + m_ledBuffer.setRGB(lednum, hue, sat, val); + //m_currentPattern = pattern; + // m_LEDController.set(m_currentPattern.getValue()); } - /** * Add your docs here. * @return */ - public LEDPatterns getPattern() { - return m_currentPattern; + public AddressableLEDBuffer getBuffer() { + return m_ledBuffer; } } \ No newline at end of file diff --git a/src/main/java/frc4388/robot/subsystems/Limelight.java b/src/main/java/frc4388/robot/subsystems/Limelight.java index 8e7da41..2200b07 100644 --- a/src/main/java/frc4388/robot/subsystems/Limelight.java +++ b/src/main/java/frc4388/robot/subsystems/Limelight.java @@ -1,165 +1,82 @@ -// // Copyright (c) FIRST and other WPILib contributors. -// // Open Source Software; you can modify and/or share it under the terms of -// // the WPILib BSD license file in the root directory of this project. +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. package frc4388.robot.subsystems; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation.Alliance; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.SubsystemBase; -// import java.io.IOException; -// import java.util.ArrayList; -// import java.util.List; -// import java.util.Optional; +import frc4388.robot.Constants.VisionConstants; -// // import org.photonvision.EstimatedRobotPose; -// // import org.photonvision.PhotonCamera; -// // import org.photonvision.PhotonPoseEstimator; -// // import org.photonvision.PhotonPoseEstimator.PoseStrategy; -// // import org.photonvision.common.hardware.VisionLEDMode; -// // import org.photonvision.targeting.PhotonPipelineResult; -// // import org.photonvision.targeting.PhotonTrackedTarget; -// // import org.photonvision.targeting.TargetCorner; +// Look at vvv for networktables stuff +// https://docs.limelightvision.io/docs/docs-limelight/apis/complete-networktables-api#apriltag-and-3d-data -// import edu.wpi.first.apriltag.AprilTag; -// import edu.wpi.first.apriltag.AprilTagFieldLayout; -// import edu.wpi.first.apriltag.AprilTagFields; -// import edu.wpi.first.math.geometry.Pose2d; -// import edu.wpi.first.wpilibj.DriverStation; -// import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -// import edu.wpi.first.wpilibj2.command.SubsystemBase; -// import frc4388.robot.Constants.VisionConstants; +public class Limelight extends SubsystemBase { -// public class Limelight extends SubsystemBase { - -// // private PhotonCamera cam; -// // private PhotonPoseEstimator photonPoseEstimator; + // // [X, Y, Z, Roll, Pitch, Yaw] + // private double[] cameraPose; + // private boolean isTag; -// private boolean lightOn; + // private Pose2d pose; + // private boolean isNearSpeaker; -// /** Creates a new Limelight. */ -// public Limelight() { -// // cam = new PhotonCamera(VisionConstants.NAME); -// // cam.setDriverMode(false); -// } + // public boolean getIsTag() { + // return isTag; + // } -// public void setLEDs(boolean on) { -// lightOn = on; -// // cam.setLED(lightOn ? VisionLEDMode.kOn : VisionLEDMode.kOff); -// } + // private void update() { + // SmartDashboard.putBoolean("Apriltag", isTag); + // if(!isTag){ + // return; + // } -// public void toggleLEDs() { -// lightOn = !lightOn; -// // cam.setLED(lightOn ? VisionLEDMode.kOn : VisionLEDMode.kOff); -// } + // double x = cameraPose[0]; + // double y = cameraPose[1]; + // double yaw = cameraPose[5]; -// public void setDriverMode(boolean driverMode) { -// // cam.setDriverMode(driverMode); -// } + // Rotation2d rot = Rotation2d.fromDegrees(yaw); -// public void setToLimePipeline() { -// // cam.setPipelineIndex(1); -// setLEDs(true); -// } + // pose = new Pose2d(x, y, rot); -// public void setToAprilPipeline() { -// // cam.setPipelineIndex(0); -// setLEDs(false); -// } - -// public PhotonTrackedTarget getAprilPoint() { -// // if (!cam.isConnected()) return null; - -// // PhotonPipelineResult result = cam.getLatestResult(); - -// // if (!result.hasTargets()) return null; - -// return result.getBestTarget(); -// } - -// private List getAprilCorners() { -// if (!cam.isConnected()) return null; - -// PhotonPipelineResult result = cam.getLatestResult(); - -// if (!result.hasTargets()) return null; - -// return result.getBestTarget().getDetectedCorners(); -// } - -// public double getAprilSkew() { -// List corners = getAprilCorners(); -// ArrayList bottomSide = getAprilBottomSide(corners); - -// if (bottomSide == null) return 0; - -// TargetCorner bottomRight = bottomSide.get(0).x > bottomSide.get(1).x ? bottomSide.get(0) : bottomSide.get(1); -// TargetCorner bottomLeft = bottomRight.x == bottomSide.get(0).x ? bottomSide.get(1) : bottomSide.get(0); - -// return bottomLeft.y - bottomRight.y; -// } - -// private ArrayList getAprilBottomSide(List box) { -// if (box == null) return null; - -// ArrayList bottomSide = new ArrayList<>(); - -// TargetCorner l1 = new TargetCorner(-1, -1); -// TargetCorner l2 = new TargetCorner(-1, -1); + // boolean isRed = DriverStation.getAlliance().get() == Alliance.Red; -// for (TargetCorner c : box) { -// if (c.y > l1.y) l1 = c; -// } + // double distance; -// for (TargetCorner c : box) { -// if (c.y == l1.y) continue; -// if (c.y > l2.y) l2 = c; -// } + // if(isRed){ + // distance = pose.getTranslation().getDistance(VisionConstants.RedSpeakerCenter); + // }else{ + // distance = pose.getTranslation().getDistance(VisionConstants.BlueSpeakerCenter); + // } + + // isNearSpeaker = distance <= VisionConstants.SpeakerBubbleDistance; -// bottomSide.add(l1); -// bottomSide.add(l2); + // //SmartDashboard.putBoolean("nearSpeaker", isNearSpeaker); + // //SmartDashboard.putNumber("speakerDistance", distance); + // } -// return bottomSide; -// } + // public Pose2d getPose() { + // return pose; + // } -// public double getDistanceToApril() { -// PhotonTrackedTarget aprilPoint = getAprilPoint(); -// if (aprilPoint == null) return -1; + // public boolean isNearSpeaker() { + // return isNearSpeaker; + // } -// double aprilHeight = VisionConstants.APRIL_HEIGHT - VisionConstants.LIME_HEIGHT; -// double theta = 35.0 + aprilPoint.getPitch(); + // @Override + // public void periodic() { + // // This method will be called once per scheduler run -// double distanceToApril = aprilHeight / Math.tan(Math.toRadians(theta)); -// return distanceToApril; -// } + // //isTag = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tv").getDouble(0.0) == 1.0; + // //double[] newPose = NetworkTableInstance.getDefault().getTable("limelight").getEntry("botpose").getDoubleArray(new double[6]); -// public PhotonTrackedTarget getLowestTape() { -// if (!cam.isConnected()) return null; - -// PhotonPipelineResult result = cam.getLatestResult(); - -// if (!result.hasTargets()) return null; - -// ArrayList points = (ArrayList) result.getTargets(); - -// PhotonTrackedTarget lowest = points.get(0); -// for (PhotonTrackedTarget point : points) { -// if (point.getPitch() < lowest.getPitch()) { -// lowest = point; -// } -// } - -// return lowest; -// } - -// public double getDistanceToTape() { -// PhotonTrackedTarget tapePoint = getLowestTape(); -// if (tapePoint == null) return -1; - -// double tapeHeight = VisionConstants.MID_TAPE_HEIGHT - VisionConstants.LIME_HEIGHT; -// double theta = 35.0 + tapePoint.getPitch(); - -// double distanceToTape = tapeHeight / Math.tan(Math.toRadians(theta)); -// return distanceToTape; -// } - -// @Override -// public void periodic() {} -// } + // //if(newPose != cameraPose){ + // // cameraPose = newPose; + // //update(); + // //} + // } +} \ No newline at end of file diff --git a/src/main/java/frc4388/robot/subsystems/Shooter.java b/src/main/java/frc4388/robot/subsystems/Shooter.java new file mode 100644 index 0000000..fb80e19 --- /dev/null +++ b/src/main/java/frc4388/robot/subsystems/Shooter.java @@ -0,0 +1,114 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc4388.robot.subsystems; + +import edu.wpi.first.wpilibj.Encoder; +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.IntakeConstants; +import frc4388.robot.Constants.ShooterConstants; + +import frc4388.robot.subsystems.Limelight; + +// import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.NeutralModeValue; +// import com.ctre.phoenix.motorcontrol.NeutralMode; + + +public class Shooter extends SubsystemBase { + + private TalonFX leftShooter; + private TalonFX rightShooter; + + private Limelight limelight; + + private int spinMode = 0; + // 0 = Stop / Coast + // 1 = Idle + // 2 = Idle Near Speaker + // 3 = Spin + // 4 = SingleSpin + + private double smartDashboardShooterSpeed; + + /** Creates a new Shooter. */ + public Shooter(TalonFX leftTalonFX, TalonFX rightTalonFX, Limelight tmplimelight) { + leftShooter = leftTalonFX; + rightShooter = rightTalonFX; + + limelight = tmplimelight; + + leftShooter.setNeutralMode(NeutralModeValue.Coast); + rightShooter.setNeutralMode(NeutralModeValue.Coast); + SmartDashboard.putNumber("Shooter Speed", ShooterConstants.SHOOTER_SPEED); + + } + + public Shooter(TalonFX leftShooter) { + this.leftShooter = leftShooter; + leftShooter.setNeutralMode(NeutralModeValue.Coast); + } + + public void singleSpin() { + leftShooter.set(1.0); + spinMode = 4; + } + + public void singleSpin(double speed) { + leftShooter.set(speed); + spinMode = 4; + } + + public void spin() { + spin(smartDashboardShooterSpeed); + spinMode = 3; + } + + public void spin(double speed) { + leftShooter.set(-speed); + rightShooter.set(-speed); + spinMode = 3; + } + + public void spin(double leftSpeed, double rightSpeed) { + leftShooter.set(leftSpeed); + rightShooter.set(-rightSpeed); + spinMode = 3; + } + + public void stop() { + spin(0.d); + spinMode = 0; + } + + public void idle() { + spin(ShooterConstants.SHOOTER_IDLE); + spinMode = 1; + } + + public int getMode(){ + return spinMode; + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + // SmartDashboard.putNumber("Left Shooter RPM", leftShooter.getRotorVelocity().getValue()); + //SmartDashboard.putNumber("Right Shooter RPM", rightShooter.getRotorVelocity().getValue()); + //smartDashboardShooterSpeed = SmartDashboard.getNumber("Shooter Speed", ShooterConstants.SHOOTER_SPEED); + + // If the robot is near the speaker, and is stopped, or idled, set to limelight idle speed. + // Else if the robot is not near the speaker, then set the speed back to idle. + // if(limelight.isNearSpeaker() && (spinMode == 0 || spinMode == 1)){ + // leftShooter.set(-ShooterConstants.SHOOTER_IDLE_LIMELIGHT); + // rightShooter.set(-ShooterConstants.SHOOTER_IDLE_LIMELIGHT); + // spinMode = 2; + // }else if(!limelight.isNearSpeaker() && spinMode == 2){ + // idle(); + // } + } +} diff --git a/src/main/java/frc4388/utility/RobotGyro.java b/src/main/java/frc4388/utility/RobotGyro.java index e1fed56..966d2e0 100644 --- a/src/main/java/frc4388/utility/RobotGyro.java +++ b/src/main/java/frc4388/utility/RobotGyro.java @@ -7,19 +7,19 @@ package frc4388.utility; -import com.ctre.phoenix.sensors.WPI_Pigeon2; +// import com.ctre.phoenix.sensors.WPI_Pigeon2; import com.ctre.phoenix6.hardware.Pigeon2; import com.kauailabs.navx.frc.AHRS; // import edu.wpi.first.wpilibj.GyroBase; -import edu.wpi.first.wpilibj.interfaces.Gyro; +// import edu.wpi.first.wpilibj.interfaces.Gyro; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.geometry.Rotation2d; /** * Gyro class that allows for interchangeable use between a pigeon and a navX */ -public class RobotGyro implements Gyro { +public class RobotGyro { private RobotTime m_robotTime = RobotTime.getInstance(); private Pigeon2 m_pigeon = null; @@ -86,7 +86,6 @@ public class RobotGyro implements Gyro { * is typically done when the robot is first turned on while it's sitting at rest before the * competition starts. */ - @Override public void calibrate() { return; // if (m_isGyroAPigeon) { @@ -96,7 +95,6 @@ public class RobotGyro implements Gyro { // } } - @Override public void reset() { resetZeroValues(); @@ -189,12 +187,10 @@ public class RobotGyro implements Gyro { return new double[] {RobotUnits.radiansToDegrees(rotation.getX() - rollZero), RobotUnits.radiansToDegrees(rotation.getY() - pitchZero), RobotUnits.radiansToDegrees(rotation.getZ())}; } - @Override public Rotation2d getRotation2d() { return m_pigeon.getRotation2d(); } - @Override public double getAngle() { if (m_isGyroAPigeon) { return getPigeonAngles()[2]; @@ -251,7 +247,6 @@ public class RobotGyro implements Gyro { } } - @Override public double getRate() { if (m_isGyroAPigeon) { return m_deltaPigeonAngle / m_robotTime.m_deltaTime * 1000; @@ -268,7 +263,6 @@ public class RobotGyro implements Gyro { return m_navX; } - @Override public void close() throws Exception { }