Skip to content

Commit

Permalink
changed trim
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Apr 5, 2024
1 parent 3994677 commit 9e92f40
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 4 deletions.
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,14 @@ private void configureBindings() {
_operatorController.triangle().whileTrue(new FeedActuate(_intakeSubsystem, ActuatorState.STOWED, FeedMode.OUTTAKE));
_operatorController.cross().whileTrue(new FeedActuate(_intakeSubsystem, ActuatorState.STOWED, FeedMode.INTAKE));

_operatorController.povUp().whileTrue(
Commands.run(() -> {
_intakeSubsystem.actuate(-0.08);
}, _intakeSubsystem).handleInterrupt(
() -> { _intakeSubsystem.actuate(0); _intakeSubsystem.resetActuator(); }
)
);

// driver bindings
_driveController.L1().onTrue(Commands.runOnce(_swerveSubsystem::toggleSpeed, _swerveSubsystem));
_driveController.R1().onTrue(Commands.runOnce(() -> _swerveSubsystem.fieldOriented = !_swerveSubsystem.fieldOriented, _swerveSubsystem));
Expand Down Expand Up @@ -206,6 +214,10 @@ private void configureBindings() {
}
}, _swerveSubsystem));

_driveController.povDown().onTrue(Commands.runOnce(() -> {
_swerveSubsystem.resetGyro(180);
}, _swerveSubsystem));

_driveController.R3().whileTrue(new NoteAlign(
_swerveSubsystem,
_visionSubsystem,
Expand Down
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ public IntakeSubsystem() {
_actuatorMotor = new CANSparkMax(Constants.CAN.INTAKE_ACTUATOR, MotorType.kBrushless);

_actuatorEncoder = _actuatorMotor.getEncoder();
_actuatorEncoder.setPosition(0);
resetActuator();

_actuatorController.setTolerance(0.5);

Expand All @@ -60,8 +60,8 @@ public IntakeSubsystem() {
_actuatorMotor.setSoftLimit(SoftLimitDirection.kForward, Constants.Encoders.INTAKE_OUT);
_actuatorMotor.setSoftLimit(SoftLimitDirection.kReverse, Constants.Encoders.INTAKE_STOWED);

_actuatorMotor.enableSoftLimit(SoftLimitDirection.kForward, true);
_actuatorMotor.enableSoftLimit(SoftLimitDirection.kReverse, true);
_actuatorMotor.enableSoftLimit(SoftLimitDirection.kForward, false);
_actuatorMotor.enableSoftLimit(SoftLimitDirection.kReverse, false);
}

public boolean hasNote() {
Expand All @@ -86,6 +86,10 @@ public void setHasNoteAuton(boolean hasNoteAuton) {
_hasNoteAuton = hasNoteAuton;
}

public void resetActuator() {
_actuatorEncoder.setPosition(0);
}

/**
* Returns true if the actuator is at the last desired state.
*/
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ public class ShooterSubsystem extends SubsystemBase {

private final Timer _revTimer = new Timer();

private double _shooterTrim = 0;
private double _shooterTrim = 5;

private boolean _holdNote = false;

Expand Down

0 comments on commit 9e92f40

Please sign in to comment.