Skip to content

Commit

Permalink
IntakeBase subsytem and command
Browse files Browse the repository at this point in the history
  • Loading branch information
StewardHail3433 committed Jan 14, 2024
1 parent e37a026 commit 698ea15
Show file tree
Hide file tree
Showing 5 changed files with 121 additions and 13 deletions.
23 changes: 22 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,36 @@

package frc.robot;

import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.commands.IntakeBaseCommand;
import frc.robot.subsystems.intake.IntakeBase;

public class RobotContainer {
public final XboxController controller;
public final IntakeBase intake;

public RobotContainer() {
controller = new XboxController(0);

boolean swerveBot = false;
boolean tankBot = false;

if (swerveBot) {
intake = null;
} else if (tankBot) {
intake = null;
} else {
intake = new IntakeBase();
}

configureBindings();
}

private void configureBindings() {}
private void configureBindings() {
intake.setDefaultCommand(new IntakeBaseCommand(intake, () -> controller.getRightBumper(), () -> controller.getLeftBumper() ));
}

public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
Expand Down
46 changes: 46 additions & 0 deletions src/main/java/frc/robot/commands/IntakeBaseCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
package frc.robot.commands;

import java.util.function.BooleanSupplier;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intake.IntakeBase;

public class IntakeBaseCommand extends Command {
IntakeBase intake;
BooleanSupplier rightBumper;
BooleanSupplier leftBumper;
public IntakeBaseCommand(IntakeBase intake, BooleanSupplier rightBumper, BooleanSupplier leftBumper) {
this.intake = intake;
this.rightBumper = rightBumper;
this.leftBumper = leftBumper;

addRequirements(intake);
}
@Override
public void initialize() {
intake.disable();
}


@Override
public void execute() {
// Turns off motors if No/All bumpers
if ((rightBumper.getAsBoolean() && leftBumper.getAsBoolean()) || (rightBumper.getAsBoolean() == false && leftBumper.getAsBoolean() == false)) {
// Disable the intake motors
intake.disable();

} else if (rightBumper.getAsBoolean()) { // Motors on (IN) if right bumper pressed
intake.setSpeed(1);

// Enable motors, It has to be called regularly for voltage compensation to work properly
intake.enable();
} else if (leftBumper.getAsBoolean()) { // Motors on (Out) if right bumper pressed
intake.setSpeed(-1);

// Enable motors, It has to be called regularly for voltage compensation to work properly
intake.enable();
} else { // Disable the intake motors
intake.disable();
}
}
}
12 changes: 0 additions & 12 deletions src/main/java/frc/robot/subsystems/Intake.java

This file was deleted.

20 changes: 20 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
package frc.robot.subsystems.intake;

public interface Intake {
/**
* Disable the speed of the motor for the intake.
*/
public default void disable() {}

/**
* Enable the speed of the motor for the intake.
*/
public default void enable() {}

/**
* Set the speed of the motor for the intake.
*
* @param speed The speed to set. Value should be between -1.0 and 1.0.
*/
public default void setSpeed(double speed) {}
}
33 changes: 33 additions & 0 deletions src/main/java/frc/robot/subsystems/intake/IntakeBase.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
package frc.robot.subsystems.intake;

import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.Spark;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class IntakeBase extends SubsystemBase implements Intake {
private final MotorController IntakeMotor;

private double voltage;

public IntakeBase() {
IntakeMotor = new Spark(0);
voltage = 0;
}

@Override
public void disable() {
voltage = 0;
IntakeMotor.setVoltage(voltage);
}

@Override
public void enable() {
IntakeMotor.setVoltage(voltage);
}

@Override
//Sets the voltage to 5.0 times speed. the speed value is -1 1
public void setSpeed(double speed) {
voltage = 5.0 * speed;
}
}

0 comments on commit 698ea15

Please sign in to comment.