Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
OakvilleDynamicsProgrammer committed Feb 17, 2024
2 parents e03d2bc + e114ee5 commit 61631a7
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 12 deletions.
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,8 @@ public static class MechanismConstants {
public static final int INTAKE_MOTOR_FRONT = 52;
public static final boolean INTAKE_MOTOR_SUSHI_INVERTED = true;
public static final boolean INTAKE_MOTOR_FRONT_INVERTED = false;
public static final double INTAKE_MOTOR_SPEED = 0.25;
public static final double INTAKE_MOTOR_SPEED_FRONT = 0.25;
public static final double INTAKE_MOTOR_SPEED_SUSHI = 0.50;

// Conveyor Motors
public static final int CONVEYOR_MOTOR_1 = 1;
Expand Down
1 change: 0 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
Expand Down
20 changes: 10 additions & 10 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,33 +11,33 @@

public class Intake extends SubsystemBase {

private final CANSparkMax intakeMotor1 =
private final CANSparkMax intakeSushi =
new CANSparkMax(MechanismConstants.INTAKE_MOTOR_SUSHI, CANSparkLowLevel.MotorType.kBrushless);
private final CANSparkMax intakeMotor2 =
private final CANSparkMax intakeFront =
new CANSparkMax(MechanismConstants.INTAKE_MOTOR_FRONT, CANSparkLowLevel.MotorType.kBrushless);

/** Creates a new Intake. */
public Intake() {
intakeMotor1.setInverted(MechanismConstants.INTAKE_MOTOR_SUSHI_INVERTED);
intakeMotor2.setInverted(MechanismConstants.INTAKE_MOTOR_FRONT_INVERTED);
intakeSushi.setInverted(MechanismConstants.INTAKE_MOTOR_SUSHI_INVERTED);
intakeFront.setInverted(MechanismConstants.INTAKE_MOTOR_FRONT_INVERTED);
}

/** Sets the intake motors to 100% power. */
public void enableIntake() {
intakeMotor1.set(MechanismConstants.INTAKE_MOTOR_SPEED * 0.66);
intakeMotor2.set(MechanismConstants.INTAKE_MOTOR_SPEED);
intakeSushi.set(MechanismConstants.INTAKE_MOTOR_SPEED_SUSHI);
intakeFront.set(MechanismConstants.INTAKE_MOTOR_SPEED_FRONT);
}

/** Sets the intake motors to 0% power. */
public void disableIntake() {
intakeMotor1.set(0);
intakeMotor2.set(0);
intakeSushi.set(0);
intakeFront.set(0);
}

/** Sets the intake motors to -100% power. (Reverse direction) */
public void reverseIntake() {
intakeMotor1.set(-MechanismConstants.INTAKE_MOTOR_SPEED * 0.66);
intakeMotor2.set(-MechanismConstants.INTAKE_MOTOR_SPEED);
intakeSushi.set(-MechanismConstants.INTAKE_MOTOR_SPEED_SUSHI);
intakeFront.set(-MechanismConstants.INTAKE_MOTOR_SPEED_FRONT);
}

@Override
Expand Down

0 comments on commit 61631a7

Please sign in to comment.