Skip to content

Commit

Permalink
Fix brake mode for intake
Browse files Browse the repository at this point in the history
Co-Authored-By: ShaneHopkins11 <97139604+ShaneHopkins11@users.noreply.github.com>
  • Loading branch information
garrettsummerfi3ld and ShaneHopkins11 committed Feb 17, 2024
1 parent 61631a7 commit 8957788
Showing 1 changed file with 7 additions and 0 deletions.
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@

import com.revrobotics.CANSparkLowLevel;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkBase.IdleMode;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.MechanismConstants;

Expand All @@ -18,8 +20,13 @@ public class Intake extends SubsystemBase {

/** Creates a new Intake. */
public Intake() {
// Set the motors to the correct inversion
intakeSushi.setInverted(MechanismConstants.INTAKE_MOTOR_SUSHI_INVERTED);
intakeFront.setInverted(MechanismConstants.INTAKE_MOTOR_FRONT_INVERTED);

// Set the idle mode to brake
intakeSushi.setIdleMode(IdleMode.kBrake);
intakeFront.setIdleMode(IdleMode.kBrake);
}

/** Sets the intake motors to 100% power. */
Expand Down

0 comments on commit 8957788

Please sign in to comment.