diff options
Diffstat (limited to 'src/main/java/frc/robot/subsystems/Intake.java')
-rw-r--r-- | src/main/java/frc/robot/subsystems/Intake.java | 12 |
1 files changed, 7 insertions, 5 deletions
diff --git a/src/main/java/frc/robot/subsystems/Intake.java b/src/main/java/frc/robot/subsystems/Intake.java index 41620bb..036aae0 100644 --- a/src/main/java/frc/robot/subsystems/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake.java @@ -11,8 +11,8 @@ import frc.robot.Constants; public class Intake extends SubsystemBase { - public static final CANSparkMax m_intakeT = new CANSparkMax(Constants.intakeT_ID, MotorType.kBrushless); - public static final CANSparkMax m_intakeD = new CANSparkMax(Constants.intakeD_ID, MotorType.kBrushless); + private final CANSparkMax m_intakeT = new CANSparkMax(Constants.intakeT_ID, MotorType.kBrushless); + private final CANSparkMax m_intakeD = new CANSparkMax(Constants.intakeD_ID, MotorType.kBrushless); private final RelativeEncoder m_intakeD_encoder = m_intakeD.getEncoder(); public Intake() @@ -26,17 +26,19 @@ public class Intake extends SubsystemBase atPercentage(perc, perc); } + // perc is between 0.0 and 1.0 public void atPercentage(double upPerc, double downPerc) { m_intakeT.set(upPerc); m_intakeD.set(downPerc); } + public void shoot() { - if (m_intakeD_encoder.getVelocity() > 2000) { - m_intakeT.set(1); + if (Math.abs(m_intakeD_encoder.getVelocity()) > 2000) { + m_intakeT.set(-0.5); } - m_intakeD.set(1); + m_intakeD.set(-0.5); } @Override |