Skip to content
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,14 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.subsystems.Intake.Intake;
import frc.robot.subsystems.Transporter.Transporter;


public class RobotContainer {
public static final Intake INTAKE = new Intake();
public static final Transporter TRANSPORTER = new Transporter();


public RobotContainer() {
configureBindings();
}
Expand Down
17 changes: 17 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,17 @@
package frc.robot.subsystems.Intake;

import com.ctre.phoenix.motorcontrol.ControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Intake extends SubsystemBase {
private final TalonSRX intakeMotor = IntakeConstants.MOTOR;

void stopMotor() {
setTargetDutyCycleOutput(0);
}

void setTargetDutyCycleOutput(double motorOutput) {
intakeMotor.set(ControlMode.PercentOutput, motorOutput);
}
}
19 changes: 19 additions & 0 deletions src/main/java/frc/robot/subsystems/Intake/IntakeCommands.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
package frc.robot.subsystems.Intake;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.StartEndCommand;
import frc.robot.RobotContainer;

public class IntakeCommands {
public static Command getSetTargetStateCommand(IntakeConstants.IntakeState targetState) {
return getSetMotorOutputCommand(targetState.targetMotorOutput);
}

private static Command getSetMotorOutputCommand(double motorOutput) {
return new StartEndCommand(
() -> RobotContainer.INTAKE.setTargetDutyCycleOutput(motorOutput),
RobotContainer.INTAKE::stopMotor,
RobotContainer.INTAKE
);
}
}
40 changes: 40 additions & 0 deletions src/main/java/frc/robot/subsystems/Intake/IntakeConstants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package frc.robot.subsystems.Intake;

import com.ctre.phoenix.motorcontrol.InvertType;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;

public class IntakeConstants {
private static final int MOTOR_ID = 5;

static final WPI_TalonSRX MOTOR = new WPI_TalonSRX(MOTOR_ID);

private static final NeutralMode NEUTRAL_MODE = NeutralMode.Brake;
private static final InvertType INVERTED_VALUE = InvertType.None;
private static final double VOLTAGE_COMPENSATION_VALUE = 12;

static {
configureMotor();
}

private static void configureMotor() {
MOTOR.configFactoryDefault();

MOTOR.setNeutralMode(NEUTRAL_MODE);
MOTOR.setInverted(INVERTED_VALUE);
MOTOR.enableVoltageCompensation(true);
MOTOR.configVoltageCompSaturation(VOLTAGE_COMPENSATION_VALUE);
}

public enum IntakeState {
COLLECT(0.5),
EJECT(-0.5),
REST(0);

final double targetMotorOutput;

IntakeState(double Output) {
this.targetMotorOutput = Output;
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -16,5 +16,4 @@ void setTargetPercentageVoltageOutput(double percentageMotorOutput) {
rightMotor.set(ControlMode.PercentOutput, percentageMotorOutput);
leftMotor.set(ControlMode.PercentOutput, percentageMotorOutput);
}
}

}
Loading