From 39c11879f949f1c1821a92c50a9e19fce862814c Mon Sep 17 00:00:00 2001 From: C4llSiqn <83995467+C4llSqin@users.noreply.github.com> Date: Tue, 29 Oct 2024 17:15:09 -0600 Subject: [PATCH] added shooter from 2024 --- src/main/java/frc4388/robot/Constants.java | 7 +++ .../java/frc4388/robot/RobotContainer.java | 9 ++++ src/main/java/frc4388/robot/RobotMap.java | 5 +++ .../frc4388/robot/subsystems/Shooter.java | 43 +++++++++++++++++++ 4 files changed, 64 insertions(+) create mode 100644 src/main/java/frc4388/robot/subsystems/Shooter.java diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index ffc8487..a0995a8 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -146,4 +146,11 @@ public final class Constants { public static final double LEFT_AXIS_DEADBAND = 0.1; } + + public static final class ShooterConstants + { + public static final int LEFT_SHOOTER_ID = 15; + public static final int RIGHT_SHOOTER_ID = 16; + public static final double SHOOTER_SPEED = 0.50; + } } diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index eeb3054..6f7feda 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -28,6 +28,8 @@ import frc4388.robot.commands.Swerve.neoJoystickPlayback; import frc4388.robot.commands.Swerve.neoJoystickRecorder; // Subsystems +import frc4388.robot.subsystems.Shooter; + // import frc4388.robot.subsystems.LED; import frc4388.robot.subsystems.SwerveDrive; @@ -47,6 +49,7 @@ public class RobotContainer { public final RobotMap m_robotMap = new RobotMap(); /* Subsystems */ + public final Shooter m_robotShooter = new Shooter(m_robotMap.leftShooter, m_robotMap.rightShooter); // private final LED m_robotLED = new LED(); public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.leftFront, @@ -151,6 +154,12 @@ public class RobotContainer { .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot())); // ? /* Operator Buttons */ + + /*Shooter*/ + + new JoystickButton(getDeadbandedOperatorController(), XboxController.LEFT_BUMPER_BUTTON) + .onTrue(new InstantCommand(() -> m_robotShooter.spin())) + .onFalse(new InstantCommand(() -> m_robotShooter.stop())); // ? /* Programer Buttons (Controller 3)*/ diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 25bf208..7eb76d8 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -11,6 +11,7 @@ import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.hardware.CANcoder; import com.ctre.phoenix6.hardware.Pigeon2; +import frc4388.robot.Constants.ShooterConstants; // import edu.wpi.first.wpilibj.motorcontrol.Spark; // import frc4388.robot.Constants.LEDConstants; import frc4388.robot.Constants.SwerveDriveConstants; @@ -55,6 +56,10 @@ public class RobotMap { public final TalonFX rightBackSteer = new TalonFX(SwerveDriveConstants.IDs.RIGHT_BACK_STEER_ID); 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); + void configureDriveMotorControllers() { // initialize SwerveModules this.rightFront = new SwerveModule(rightFrontWheel, rightFrontSteer, rightFrontEncoder, SwerveDriveConstants.DefaultSwerveRotOffsets.FRONT_RIGHT_ROT_OFFSET); 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..98d39a0 --- /dev/null +++ b/src/main/java/frc4388/robot/subsystems/Shooter.java @@ -0,0 +1,43 @@ +// 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.wpilibj2.command.SubsystemBase; +import frc4388.robot.Constants.ShooterConstants; + +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.NeutralModeValue; + +public class Shooter extends SubsystemBase { + private TalonFX leftShooter; + private TalonFX rightShooter; + /** Creates a new Shooter. */ + public Shooter(TalonFX leftShooterMotor, TalonFX rightShooterMotor) { + leftShooter = leftShooterMotor; + rightShooter = rightShooterMotor; + + leftShooter.setNeutralMode(NeutralModeValue.Coast); + rightShooter.setNeutralMode(NeutralModeValue.Coast); + } + + public void spin(double speed) { + leftShooter.set(speed); + rightShooter.set(speed); + } + + public void spin() { + spin(ShooterConstants.SHOOTER_SPEED); + } + + public void stop() { + spin(0); + } + + + @Override + public void periodic() { + // This method will be called once per scheduler run + } +}