Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 2 additions & 4 deletions src/main/java/frc/robot/subsystems/funnel/Funnel.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,11 +21,8 @@ public Funnel() {
io = Robot.isReal() ? new FunnelIOSparksMax(this.fieldsTable) : new FunnelIOSim(this.fieldsTable);
}

public void setMotorVoltage(double voltageDemand) {
io.setVoltage(MathUtil.clamp(voltageDemand, -MOTOR_MAX_VOLTAGE, MOTOR_MAX_VOLTAGE));
}

public void setMotorPercentageSpeed(double percentageSpeed) {
fieldsTable.recordOutput("precentage speed", percentageSpeed);
io.setPercentageSpeed(MathUtil.clamp(percentageSpeed, -1, 1));
}

Expand All @@ -34,6 +31,7 @@ public boolean getIsCoralIn() {
}

public void stop() {
fieldsTable.recordOutput("precentage speed", 0);
io.setPercentageSpeed(0);
}
}
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/subsystems/funnel/io/FunnelIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,6 @@ public FunnelIO(LogFieldsTable fieldsTable) {
}

// Inputs:
public abstract void setVoltage(double voltageDemand);

public abstract void setPercentageSpeed(double percentageSpeed);

// Outputs:
Expand Down
5 changes: 0 additions & 5 deletions src/main/java/frc/robot/subsystems/funnel/io/FunnelIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,15 +3,10 @@
import frc.lib.logfields.LogFieldsTable;

public class FunnelIOSim extends FunnelIO {

public FunnelIOSim(LogFieldsTable fieldsTable) {
super(fieldsTable);
}

@Override
public void setVoltage(double voltageDemand) {
}

@Override
public void setPercentageSpeed(double percentageSpeed) {
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,26 +15,21 @@
import static frc.robot.subsystems.funnel.FunnelConstants.MAX_CURRENT;

public class FunnelIOSparksMax extends FunnelIO {
private SparkMax funnelMotor = new SparkMax(CANBUS.FUNNEL_MOTOR_ID, MotorType.kBrushless);
private SparkMax motor = new SparkMax(CANBUS.FUNNEL_MOTOR_ID, MotorType.kBrushless);
private DigitalInput beamBrake = new DigitalInput(FUNNEL_BEAM_BRAKE_ID);

private SparkMaxConfig motorConfig = new SparkMaxConfig();

public FunnelIOSparksMax(LogFieldsTable fieldsTable) {
super(fieldsTable);
motorConfig.smartCurrentLimit(MAX_CURRENT);
motorConfig.idleMode(IdleMode.kBrake);
funnelMotor.configure(motorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
}

@Override
public void setVoltage(double voltageDemand) {
funnelMotor.setVoltage(voltageDemand);
motor.configure(motorConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
}

@Override
public void setPercentageSpeed(double percentageSpeed) {
funnelMotor.set(percentageSpeed);
motor.set(percentageSpeed);
}

@Override
Expand All @@ -44,6 +39,6 @@ protected boolean getIsCoralIn() {

@Override
protected double getCurrent() {
return funnelMotor.getOutputCurrent();
return motor.getOutputCurrent();
}
}
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/gripper/Gripper.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.math.filter.Debouncer.DebounceType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.lib.logfields.LogFieldsTable;
import frc.robot.Robot;
Expand All @@ -13,7 +14,7 @@

public class Gripper extends SubsystemBase {
private final LogFieldsTable fieldsTable = new LogFieldsTable(getName());
private final Debouncer isCoralInDebouncer = new Debouncer(DEBOUNCER_SECONDS);
private final Debouncer isCoralInDebouncer = new Debouncer(DEBOUNCER_SECONDS, DebounceType.kBoth);

private final GripperIO io = Robot.isReal() ?
new GripperIOSparkMax(fieldsTable) :
Expand Down
16 changes: 9 additions & 7 deletions src/main/java/frc/robot/subsystems/gripper/GripperCommands.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,21 +8,23 @@

public class GripperCommands {
Gripper gripper;

public GripperCommands(Gripper gripper) {
this.gripper = gripper;
}

public Command spin(double backVoltageForScoring, double rightVoltageForScoring, double leftVoltageForScoring) {
return gripper.run(() -> gripper.setMotorsVoltages(rightVoltageForScoring, leftVoltageForScoring, backVoltageForScoring))
.finallyDo(gripper::stop).withName("spin gripper");
return gripper.run(
() -> gripper.setMotorsVoltages(rightVoltageForScoring, leftVoltageForScoring, backVoltageForScoring))
.finallyDo(gripper::stop).withName("spin gripper");
}

public Command manualController(DoubleSupplier backSpeed, DoubleSupplier rightSpeed, DoubleSupplier leftSpeed) {
return gripper.run(() ->
gripper.setMotorsVoltages(backSpeed.getAsDouble() * OUTTAKE_MOTORS_MAX_VOLTAGE,
rightSpeed.getAsDouble() * OUTTAKE_MOTORS_MAX_VOLTAGE, leftSpeed.getAsDouble() * OUTTAKE_MOTORS_MAX_VOLTAGE))
.finallyDo(gripper::stop).withName("gripper manual controller");
return gripper.run(() -> gripper.setMotorsVoltages(
backSpeed.getAsDouble() * BACK_MOTOR_MAX_VOLTAGE,
rightSpeed.getAsDouble() * OUTTAKE_MOTORS_MAX_VOLTAGE,
leftSpeed.getAsDouble() * OUTTAKE_MOTORS_MAX_VOLTAGE))
.finallyDo(gripper::stop).withName("gripper manual controller");
}

}