diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index f915b1f0..fbe16664 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -90,8 +90,15 @@ public static class IntakeConstants { public static final double pastsensortime = 0.5; } + public static class ShooterConstants { + public static final int LIMIT_SWITCH_ID = 1; + public static final int PIVOT_MOTOR_ID = 12; + public static final int SHOOTER_MOTOR_ONE_ID = 13; + public static final int SHOOTER_MOTOR_TWO_ID = 14; + public static final int FEEDER_MOTOR_ID = 10; + } public static class ClimbConstants { public static final int LEFT_WINCH_MOTOR_ID = 8; diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java index ab2010c5..a7f6527e 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java @@ -3,7 +3,7 @@ import com.ctre.phoenix.motorcontrol.TalonSRXControlMode; import com.ctre.phoenix.motorcontrol.can.TalonSRX; import com.revrobotics.ColorSensorV3; - +import static frc.robot.Constants.ShooterConstants.*; import edu.wpi.first.wpilibj.I2C; import edu.wpi.first.wpilibj2.command.SubsystemBase; @@ -22,8 +22,7 @@ public class ShooterFeederSubsystem extends SubsystemBase{ public ShooterFeederSubsystem(){ //motors - feederMotor = new TalonSRX(15); - + feederMotor = new TalonSRX(FEEDER_MOTOR_ID); feederMotor.setInverted(true); //sensors diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterFlywheelSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterFlywheelSubsystem.java index c86fcc4e..a24abbd2 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterFlywheelSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterFlywheelSubsystem.java @@ -4,6 +4,7 @@ //create enums, expecting, holding, firing, and no note package frc.robot.subsystems.shooter; +import static frc.robot.Constants.ShooterConstants.*; import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkBase.IdleMode; import com.revrobotics.CANSparkLowLevel.MotorType; @@ -13,6 +14,8 @@ public class ShooterFlywheelSubsystem extends SubsystemBase { //change later (ALL OF THEM ARE PLACEHOLDERS) int IDNUMBER = 10; //so I remember to change them later + // public static final int SHOOTER_MOTOR_ONE_ID = 13; + // public static final int SHOOTER_MOTOR_TWO_ID = 14; public final double SHOOTER_MOTOR_SPEED = 1; //motors @@ -26,8 +29,8 @@ public class ShooterFlywheelSubsystem extends SubsystemBase { public ShooterFlywheelSubsystem(){ //motors - shooterMotor = new CANSparkMax(13, MotorType.kBrushless); - shooterMotorTwo = new CANSparkMax(14, MotorType.kBrushless); + shooterMotor = new CANSparkMax(SHOOTER_MOTOR_ONE_ID, MotorType.kBrushless); + shooterMotorTwo = new CANSparkMax(SHOOTER_MOTOR_TWO_ID, MotorType.kBrushless); shooterMotor.setIdleMode(IdleMode.kCoast); shooterMotorTwo.setIdleMode(IdleMode.kCoast); diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterPivotSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterPivotSubsystem.java index 6e27e262..e5144f58 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterPivotSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterPivotSubsystem.java @@ -9,6 +9,8 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import static frc.robot.Constants.ShooterConstants.*; + public class ShooterPivotSubsystem extends SubsystemBase { @@ -49,7 +51,7 @@ public class ShooterPivotSubsystem extends SubsystemBase { public ShooterPivotSubsystem(boolean alliance){ //motors - pivotMotor = new CANSparkMax(12, MotorType.kBrushless); + pivotMotor = new CANSparkMax(PIVOT_MOTOR_ID, MotorType.kBrushless); pivotMotor.setInverted(true); //devices