Skip to content

Commit

Permalink
Merge branch 'Trigger' into 27-handoff-command
Browse files Browse the repository at this point in the history
  • Loading branch information
Jacob1010-h committed Jan 23, 2024
2 parents f2b44bb + b0dc755 commit 5a9cf63
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 11 deletions.
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ public class RobotContainer implements Logged {
private final Intake intake;
@SuppressWarnings("unused")
private final DriverUI driverUI;
private final TriggerWheel triggerWheel;

private final Limelight limelight;
private final Climb climb;
Expand All @@ -48,6 +49,7 @@ public RobotContainer() {
swerve = new Swerve();
driverUI = new DriverUI();
triggerWheel = new TriggerWheel();
<<<<<<< HEAD

limelight.setDefaultCommand(Commands.run(() -> {
// Create an "Optional" object that contains the estimated pose of the robot
Expand All @@ -63,6 +65,8 @@ public RobotContainer() {
DriverUI.currentTimestamp - limelight.getCombinedLatencySeconds());
}
}, limelight));
=======
>>>>>>> Trigger

swerve.setDefaultCommand(new Drive(
swerve,
Expand Down
22 changes: 11 additions & 11 deletions src/main/java/frc/robot/subsystems/TriggerWheel.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,26 +3,26 @@
import com.revrobotics.CANSparkLowLevel.PeriodicFrame;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import java.util.function.BooleanSupplier;
import frc.robot.util.Constants.IntakeConstants;
import frc.robot.util.Neo;
import java.util.Optional;
import frc.robot.util.Constants.TriggerWheelConstants;

public class TriggerWheel extends SubsystemBase {
private final Neo triggerWheel;
private Optional<boolean> whichWay;
private Optional<Boolean> whichWay;
private BooleanSupplier hasPiece;

public TriggerWheel() {
TriggerWheel = new Neo(TriggerWheelConstants.TRIGGER_WHEEL_CAN_ID);
triggerWheel = new Neo(IntakeConstants.TRIGGER_WHEEL_CAN_ID);
whichWay = Optional.empty();
hasPiece = () -> false;
configMotor();
}

public void configMotor() {
// See https://docs.revrobotics.com/sparkmax/operating-modes/control-interfaces
triggerWheel.setSmartCurrentLimit(TriggerWheelConstants.TRIGGERWHEEL_STALL_CURRENT_LIMIT_AMPS, TriggerWheelConstants.TRIGGERWHEEL_FREE_CURRENT_LIMIT_AMPS);
triggerWheel.setSmartCurrentLimit(IntakeConstants.TRIGGER_WHEEL_STALL_CURRENT_LIMIT_AMPS, IntakeConstants.TRIGGER_WHEEL_FREE_CURRENT_LIMIT_AMPS);
triggerWheel.setPeriodicFramePeriod(PeriodicFrame.kStatus3, 65535);
triggerWheel.setPeriodicFramePeriod(PeriodicFrame.kStatus5, 65535);
triggerWheel.setInverted(false);
Expand All @@ -31,30 +31,30 @@ public void configMotor() {
triggerWheel.setBrakeMode();
}

public Optional<boolean> whichWay(){
public Optional<Boolean> whichWay(){
return whichWay;
}

public Command toShooter() {
whichWay = Optional.ofNullable(true);
return runOnce(() -> triggerWheel.set(TriggerWheelConstants.SHOOTER_TRIGGER_WHEEL_SPEED));
return runOnce(() -> triggerWheel.set(IntakeConstants.SHOOTER_TRIGGER_WHEEL_SPEED));
}

public Command toTrap() {
whichWay = Optional.ofNullable(false);
return runOnce(() -> triggerWheel.set(TriggerWheelConstants.TRAP_TRIGGER_WHEEL_SPEED));
return runOnce(() -> triggerWheel.set(IntakeConstants.TRAP_TRIGGER_WHEEL_SPEED));
}

public Command stopCommand() {
whichWay = Optional.empty();
return runOnce(() -> triggerWheel.set(TriggerWheelConstants.STOP_SPEED));
return runOnce(() -> triggerWheel.set(IntakeConstants.STOP_SPEED));
}

public BooleanSupplier hasPiece() {
return hasPiece;
return this.hasPiece;
}

public void setHasPiece(boolean hasPiece) {
hasPiece = () -> hasPiece;
this.hasPiece = () -> hasPiece;
}
}
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/util/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -306,6 +306,12 @@ public static final class IntakeConstants {
public static final int INTAKE_STALL_CURRENT_LIMIT_AMPS = 7;

public static final int HAS_PIECE_CURRENT_THRESHOLD = 20;

// TODO: Add these to the robot
public static final int TRIGGER_WHEEL_STALL_CURRENT_LIMIT_AMPS = 0;
public static final int TRIGGER_WHEEL_FREE_CURRENT_LIMIT_AMPS = 0;
public static final double SHOOTER_TRIGGER_WHEEL_SPEED = 0;
public static final double TRAP_TRIGGER_WHEEL_SPEED = 0;
}

public static final class FieldConstants {
Expand Down

0 comments on commit 5a9cf63

Please sign in to comment.