Skip to content

Commit

Permalink
Logging maybe fixed
Browse files Browse the repository at this point in the history
  • Loading branch information
DerekChen1 committed Dec 6, 2023
1 parent 098cc25 commit 374b3a2
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 17 deletions.
18 changes: 17 additions & 1 deletion src/main/java/frc/robot/subsystems/IntakeIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,30 @@

import frc.robot.subsystems.IntakeSubsystem.Modes;
import org.littletonrobotics.junction.AutoLog;
import org.littletonrobotics.junction.LogTable;
import org.littletonrobotics.junction.inputs.LoggableInputs;

public interface IntakeIO {
@AutoLog
public static class IntakeIOInputs {
public static class IntakeIOInputs implements LoggableInputs {
public String currentIntakeMode = Modes.OFF.toString();
public double filterOutput = 0.0;
public boolean isCone = false;
public double motorOutput = 0.0;

public void toLog(LogTable table) {
table.put("IntakeMode", currentIntakeMode);
table.put("FilterOutput", filterOutput);
table.put("IsCone", isCone);
table.put("MotorOutput", motorOutput);
}

public void fromLog(LogTable table) {
currentIntakeMode = table.getString("IntakeMode", currentIntakeMode);
filterOutput = table.getDouble("FilterOutput", filterOutput);
motorOutput = table.getDouble("MotorOutput", motorOutput);
isCone = table.getBoolean("IsCone", isCone);
}
}

/** Updates the set of loggable inputs. */
Expand Down
6 changes: 2 additions & 4 deletions src/main/java/frc/robot/subsystems/IntakeIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,13 @@
public class IntakeIOTalonFX extends SubsystemBase {
private TalonFX intakeMotor;
private ShuffleboardTab shuffleboard = Shuffleboard.getTab("Intake Subsystem");
private IntakeSubsystem intakeSubsystem;
private LinearFilter filter;
private double filterOutput;
private boolean isCone;
// private final TimeOfFlight coneToF, cubeToF;

/** Creates a new IntakeIOTalonFX. */
public IntakeIOTalonFX(IntakeSubsystem intakeSubsystem) {
this.intakeSubsystem = intakeSubsystem;
public IntakeIOTalonFX() {

intakeMotor = new TalonFX(Constants.Intake.Ports.INTAKE_MOTOR_PORT);

Expand Down Expand Up @@ -64,7 +62,7 @@ public double getFilterOutput() {
}

public void updateInputs(IntakeIOInputs inputs) {
inputs.currentIntakeMode = intakeSubsystem.getMode().toString();
inputs.currentIntakeMode = inputs.currentIntakeMode.toString();
inputs.filterOutput = getFilterOutput();
inputs.isCone = getIsCone();
inputs.motorOutput = getMotorPower();
Expand Down
25 changes: 13 additions & 12 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,11 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.Intake;
import frc.robot.subsystems.IntakeIO.IntakeIOInputs;
import org.littletonrobotics.junction.Logger;

public class IntakeSubsystem extends SubsystemBase {
private final IntakeIO io;
private final IntakeIOInputs inputs = new IntakeIOInputs();
private final IntakeIOTalonFX motorIO = new IntakeIOTalonFX(this);
private Modes mode;
private ShuffleboardTab shuffleboard = Shuffleboard.getTab("Intake Subsystem");

Expand All @@ -24,9 +24,9 @@ public IntakeSubsystem(IntakeIO io) {
this.io = io;

shuffleboard.addString("Current mode", () -> mode.toString());
shuffleboard.addDouble("filter output", () -> motorIO.getFilterOutput());
shuffleboard.addDouble("motor output", () -> motorIO.getMotorPower());
shuffleboard.addBoolean("is cube intake", () -> motorIO.getIsCone());
shuffleboard.addDouble("filter output", () -> inputs.filterOutput);
shuffleboard.addDouble("motor output", () -> inputs.motorOutput);
shuffleboard.addBoolean("is cube intake", () -> inputs.isCone);
}

// These modes should probably be in the IntakeIOTalonFX class
Expand All @@ -46,32 +46,32 @@ public void setMode(Modes mode) {
}

public void setIsCone(boolean isCone) {
motorIO.setIsCone(isCone);
inputs.isCone = isCone;
}

public double getFilterOutput() {
return motorIO.getFilterOutput();
return inputs.filterOutput;
}

public void intakePeriodic(Modes modes) {

switch (modes) {
case INTAKE:
if (motorIO.getIsCone()) {
if (inputs.isCone) {
io.setMotorPower(Intake.INTAKE_CONE_PERCENT);
} else {
io.setMotorPower(Intake.INTAKE_CUBE_PERCENT);
}
break;
case OUTTAKE:
if (motorIO.getIsCone()) {
if (inputs.isCone) {
io.setMotorPower(Intake.OUTTAKE_CONE_PERCENT);
} else {
io.setMotorPower(Intake.OUTTAKE_CUBE_PERCENT);
}
break;
case HOLD:
if (motorIO.getIsCone()) {
if (inputs.isCone) {
io.setMotorPower(Intake.HOLD_CONE_PERCENT);
} else {
io.setMotorPower(Intake.HOLD_CUBE_PERCENT);
Expand All @@ -86,15 +86,16 @@ public void intakePeriodic(Modes modes) {

@Override
public void periodic() {
double filterOutput = motorIO.getFilterOutput();
if (motorIO.getIsCone() && filterOutput >= Intake.CONE_STATOR_LIMIT) {
if (inputs.isCone && inputs.filterOutput >= Intake.CONE_STATOR_LIMIT) {
mode = Modes.HOLD;
} else if (filterOutput >= Intake.CUBE_STATOR_LIMIT) {
} else if (inputs.filterOutput >= Intake.CUBE_STATOR_LIMIT) {
mode = Modes.HOLD;
}

intakePeriodic(mode);

io.updateInputs(inputs);

Logger.getInstance().processInputs("Intake", inputs);
}
}

0 comments on commit 374b3a2

Please sign in to comment.