From c8bc774a668d2d5cd08bc5846d8c981247112785 Mon Sep 17 00:00:00 2001 From: McGrathMaggie <78870mm@gmail.com> Date: Tue, 29 Oct 2024 17:54:21 -0600 Subject: [PATCH] added 2024 shooter code --- src/main/java/frc4388/robot/Constants.java | 6 +++ .../java/frc4388/robot/RobotContainer.java | 8 +++- src/main/java/frc4388/robot/RobotMap.java | 6 +++ .../frc4388/robot/subsystems/Shooter.java | 43 +++++++++++++++++++ 4 files changed, 62 insertions(+), 1 deletion(-) 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..1d62112 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -132,6 +132,12 @@ public final class Constants { public static final class DriveConstants { public static final int SMARTDASHBOARD_UPDATE_FRAME = 2; } + + public static final class ShooterConstants { + public static final double SHOOTER_SPEED = .5; + public static final int LEFT_SHOOTER_ID = 15; + public static final int RIGHT_SHOOTER_ID = 16; + } public static final class LEDConstants { public static final int LED_SPARK_ID = 0; diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index eeb3054..9f6a83e 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -26,7 +26,7 @@ import edu.wpi.first.wpilibj2.command.RunCommand; import frc4388.utility.controller.VirtualController; import frc4388.robot.commands.Swerve.neoJoystickPlayback; import frc4388.robot.commands.Swerve.neoJoystickRecorder; - +import frc4388.robot.subsystems.Shooter; // Subsystems // import frc4388.robot.subsystems.LED; import frc4388.robot.subsystems.SwerveDrive; @@ -56,6 +56,8 @@ public class RobotContainer { m_robotMap.gyro); + public final Shooter m_robotShooter = new Shooter(m_robotMap.leftShooter, m_robotMap.rightShooter); + /* Controllers */ private final DeadbandedXboxController m_driverXbox = new DeadbandedXboxController(OIConstants.XBOX_DRIVER_ID); private final DeadbandedXboxController m_operatorXbox = new DeadbandedXboxController(OIConstants.XBOX_OPERATOR_ID); @@ -151,6 +153,10 @@ public class RobotContainer { .onTrue(new InstantCommand(() -> m_robotSwerveDrive.shiftUpRot())); // ? /* Operator Buttons */ + + DualJoystickButton(getDeadbandedOperatorController(), getVirtualOperatorController(), XboxController.LEFT_BUMPER_BUTTON) + .onTrue(new InstantCommand(() -> m_robotShooter.spin(), m_robotShooter)) + .onFalse(new InstantCommand(() -> m_robotShooter.stop(), m_robotShooter)); // ? /* Programer Buttons (Controller 3)*/ diff --git a/src/main/java/frc4388/robot/RobotMap.java b/src/main/java/frc4388/robot/RobotMap.java index 25bf208..0ac83b5 100644 --- a/src/main/java/frc4388/robot/RobotMap.java +++ b/src/main/java/frc4388/robot/RobotMap.java @@ -11,9 +11,11 @@ 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; +import frc4388.robot.subsystems.Shooter; import frc4388.robot.subsystems.SwerveModule; import frc4388.utility.RobotGyro; @@ -55,6 +57,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..877a78f --- /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 com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.NeutralModeValue; + +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc4388.robot.Constants.ShooterConstants; +import frc4388.robot.Constants; + +public class Shooter extends SubsystemBase { + /** Creates a new Shooter. */ + TalonFX leftShooter; + TalonFX rightShooter; + + public Shooter(TalonFX leftShooter, TalonFX rightShooter) { + this.leftShooter = leftShooter; + this.rightShooter = rightShooter; + 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 + } +}