diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/CommandTeleOp.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/CommandTeleOp.java index 4938d86..96bc0a6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/CommandTeleOp.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/CommandTeleOp.java @@ -136,7 +136,7 @@ public void initialize() { leftTrigger.whileActiveContinuous( - new IntakeCommand(feeder, () -> beamBreak.isBeamBreakOn(), Constants.Feeder.DEFAULT_INTAKE_POWER, 0.6) + new IntakeCommand(feeder, () -> beamBreak.isBeamBreakOn(), Constants.Feeder.DEFAULT_INTAKE_POWER, 0) ); leftBumper.whileActiveContinuous( new IntakeCommand(feeder, () -> false, -Constants.Feeder.DEFAULT_INTAKE_POWER, -Constants.Feeder.DEFAULT_INDEX_POWER) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Commands/IntakeCommand.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Commands/IntakeCommand.java index f3e0d95..81853f7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Commands/IntakeCommand.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Commands/IntakeCommand.java @@ -13,7 +13,8 @@ public class IntakeCommand extends CommandBase { private BooleanSupplier breamBreak; private double intakePower, indexPower; private static final long INDEX_FEED_PULSE_MS = 180L; - private static final double INDEX_FEED_PULSE_POWER = 0.6; + private static final double INDEX_FEED_PULSE_POWER_INTAKE = 0.35; + private static final double INDEX_FEED_PULSE_POWER_ACTIVE = 0.6; private boolean beamBlockedLatched; private long indexFeedUntilNanos; @@ -66,11 +67,11 @@ public void execute() { private double getIndexPulsePower() { if (Math.abs(indexPower) < 1e-6) { - return INDEX_FEED_PULSE_POWER; + return INDEX_FEED_PULSE_POWER_INTAKE; } return Math.copySign( - Math.min(Math.abs(indexPower), INDEX_FEED_PULSE_POWER), + Math.min(Math.abs(indexPower), INDEX_FEED_PULSE_POWER_ACTIVE), indexPower ); }