Skip to content

Commit

Permalink
Merge branch 'main' into drive-integration
Browse files Browse the repository at this point in the history
  • Loading branch information
linglejack06 authored Oct 8, 2024
2 parents 9c05744 + 7ab84f2 commit 7865309
Show file tree
Hide file tree
Showing 13 changed files with 68 additions and 67 deletions.
48 changes: 24 additions & 24 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,9 @@
"/SmartDashboard/Module 0": "Mechanism2d",
"/SmartDashboard/Module 1": "Mechanism2d",
"/SmartDashboard/Module 2": "Mechanism2d",

"/SmartDashboard/Module 3": "Mechanism2d",
"/SmartDashboard/PhotonSimField": "Field2d",
"/SmartDashboard/VisionSystemSim-main/Sim Field": "Field2d",
"/AdvantageKit/RealOutputs/scoring/mechanism2d": "Mechanism2d"
"/SmartDashboard/VisionSystemSim-main/Sim Field": "Field2d"
}
},
"NetworkTables": {
Expand All @@ -32,30 +30,32 @@
},
"NetworkTables Info": {
"Connections": {
"Server": {
"Publishers": {
"Server": {
"Publishers": {
"open": true
},
"open": true
},
"open": true
"visible": true
},
"visible": true
},
"Plot": {
"Plot <0>": {
"plots": [
{
"backgroundColor": [
0.0,
0.0,
0.0,
0.8500000238418579
],
"height": 338
"Plot": {
"Plot <0>": {
"plots": [
{
"backgroundColor": [
0.0,
0.0,
0.0,
0.8500000238418579
],
"height": 338
}
],
"window": {
"visible": false
}
],
"window": {
"visible": false
}
}
},
"visible": true
}
}}
}
28 changes: 14 additions & 14 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGReader;
import org.littletonrobotics.junction.wpilog.WPILOGWriter;

public class Robot extends LoggedRobot {
Expand All @@ -37,19 +36,20 @@ public void robotInit() {
setUseTiming(false);
Logger.addDataReceiver(new WPILOGWriter("logs/")); // This folder is gitignored
Logger.addDataReceiver(new NT4Publisher());
} else {
setUseTiming(false); // Run as fast as possible
String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope
// (or prompt the user)
Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log
Logger.addDataReceiver(
new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // Save
// outputs
// to
// a
// new
// log
}
} /*TODO: Fix replay mode!
else {
setUseTiming(false); // Run as fast as possible
String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope
// (or prompt the user)
Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log
Logger.addDataReceiver(
new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // Save
// outputs
// to
// a
// new
// log
}*/
Logger.start();
}

Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/intake/IntakeIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
public interface IntakeIO {

@AutoLog
public static class IntakeIOInputs {
public static class IntakeInputs {
public double intakeMotorVoltage = 0.0;
public double intakeMotorStatorCurrentAmps = 0.0;
public double intakeMotorSupplyCurrentAmps = 0.0;
Expand All @@ -18,15 +18,15 @@ public static class IntakeIOInputs {
}

@AutoLog
public static class IntakeIOOutputs {
public static class IntakeOutputs {
public double intakeMotorVoltage = 0.0;

public double centeringMotorVoltage = 0.0;
}

public default void updateInputs(IntakeIOInputs inputs) {}
public default void updateInputs(IntakeInputs inputs) {}

public default void applyOutputs(IntakeIOOutputs outputs) {}
public default void applyOutputs(IntakeOutputs outputs) {}

public default void setIntakeVoltage(double volts) {}

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/intake/IntakeIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ public class IntakeIOSim implements IntakeIO {
public IntakeIOSim() {}

@Override
public void updateInputs(IntakeIOInputs inputs) {
public void updateInputs(IntakeInputs inputs) {
// inputs.leftIntakeVoltage = intakeWheelsAppliedVolts;
// inputs.leftIntakeStatorCurrent = noteInIntakeWheels ? 100000 : 0;
// inputs.rightIntakeVoltage = intakeWheelsAppliedVolts;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public IntakeNEOVortex() {
}

@Override
public void updateInputs(IntakeIOInputs inputs) {
public void updateInputs(IntakeInputs inputs) {
inputs.intakeMotorVoltage = intakeMotor.getAppliedOutput();
inputs.intakeMotorStatorCurrentAmps = intakeMotor.getOutputCurrent();

Expand All @@ -37,7 +37,7 @@ public void updateInputs(IntakeIOInputs inputs) {
}

@Override
public void applyOutputs(IntakeIOOutputs outputs) {
public void applyOutputs(IntakeOutputs outputs) {
outputs.intakeMotorVoltage = intakeMotorVolts;

outputs.centeringMotorVoltage = centeringMotorVolts;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,9 @@
public class IntakeSubsystem extends SubsystemBase {

private IntakeIO io;
private IntakeIOInputsAutoLogged inputs = new IntakeIOInputsAutoLogged();
private IntakeIOOutputsAutoLogged outputs = new IntakeIOOutputsAutoLogged();
private IntakeInputsAutoLogged inputs = new IntakeInputsAutoLogged();
private IntakeOutputsAutoLogged outputs = new IntakeOutputsAutoLogged();

private State state = State.IDLE;

private BooleanSupplier scorerWantsNote = () -> true;
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/scoring/AimerIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

public interface AimerIO {
@AutoLog
public static class AimerIOInputs {
public static class AimerInputs {
public double aimAngleRad = 0.0;
public double aimGoalAngleRad = 0.0;
public double aimProfileGoalAngleRad = 0.0;
Expand All @@ -17,13 +17,13 @@ public static class AimerIOInputs {
}

@AutoLog
public static class AimerIOOutputs {
public static class AimerOutputs {
public double aimAppliedVoltage = 0.0;
}

public default void updateInputs(AimerIOInputs inputs) {}
public default void updateInputs(AimerInputs inputs) {}

public default void applyOutputs(AimerIOOutputs outputs) {}
public default void applyOutputs(AimerOutputs outputs) {}

public default void setAimAngleRad(double angle, boolean newProfile) {}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ public void setMotorDisabled(boolean disabled) {
}

@Override
public void updateInputs(AimerIOInputs inputs) {
public void updateInputs(AimerInputs inputs) {

if (getEncoderPosition() == -1.75) {
motorDisabled = true;
Expand Down Expand Up @@ -211,7 +211,7 @@ public void updateInputs(AimerIOInputs inputs) {
}

@Override
public void applyOutputs(AimerIOOutputs outputs) {
public void applyOutputs(AimerOutputs outputs) {

State trapezoidSetpoint =
profile.calculate(
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/scoring/AimerIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ public void setPID(double p, double i, double d) {
}

@Override
public void updateInputs(AimerIOInputs inputs) {
public void updateInputs(AimerInputs inputs) {
sim.update(SimConstants.loopTime);

inputs.aimGoalAngleRad = goalAngleRad;
Expand All @@ -116,7 +116,7 @@ public void updateInputs(AimerIOInputs inputs) {
}

@Override
public void applyOutputs(AimerIOOutputs outputs) {
public void applyOutputs(AimerOutputs outputs) {
State trapezoidSetpoint =
profile.calculate(
timer.get(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,12 @@

public class ScoringSubsystem extends SubsystemBase implements Tunable {
private final ShooterIO shooterIo;
private final ShooterIOInputsAutoLogged shooterInputs = new ShooterIOInputsAutoLogged();
private final ShooterIOOutputsAutoLogged shooterOutputs = new ShooterIOOutputsAutoLogged();
private final ShooterInputsAutoLogged shooterInputs = new ShooterInputsAutoLogged();
private final ShooterOutputsAutoLogged shooterOutputs = new ShooterOutputsAutoLogged();

private final AimerIO aimerIo;
private final AimerIOInputsAutoLogged aimerInputs = new AimerIOInputsAutoLogged();
private final AimerIOOutputsAutoLogged aimerOutputs = new AimerIOOutputsAutoLogged();
private final AimerInputsAutoLogged aimerInputs = new AimerInputsAutoLogged();
private final AimerOutputsAutoLogged aimerOutputs = new AimerOutputsAutoLogged();

private final Timer shootTimer = new Timer();

Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/scoring/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

public interface ShooterIO {
@AutoLog
public static class ShooterIOInputs {
public static class ShooterInputs {
public double shooterLeftVelocityRPM = 0.0;
public double shooterLeftAppliedVolts = 0.0;
public double shooterLeftStatorCurrentAmps = 0.0;
Expand All @@ -22,17 +22,17 @@ public static class ShooterIOInputs {
}

@AutoLog
public static class ShooterIOOutputs {
public static class ShooterOutputs {
public double shooterLeftGoalVelocityRPM = 0.0;

public double shooterRightGoalVelocityRPM = 0.0;

public double kickerGoalVolts = 0.0;
}

public default void updateInputs(ShooterIOInputs inputs) {}
public default void updateInputs(ShooterInputs inputs) {}

public default void applyOutputs(ShooterIOOutputs outputs) {}
public default void applyOutputs(ShooterOutputs outputs) {}

public default void setShooterVelocityRPM(double velocity) {}

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/scoring/ShooterIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ public void setPID(double p, double i, double d) {
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
public void updateInputs(ShooterInputs inputs) {
shooterLeftSim.update(SimConstants.loopTime);
shooterRightSim.update(SimConstants.loopTime);

Expand All @@ -95,7 +95,7 @@ public void updateInputs(ShooterIOInputs inputs) {
}

@Override
public void applyOutputs(ShooterIOOutputs outputs) {
public void applyOutputs(ShooterOutputs outputs) {

outputs.shooterLeftGoalVelocityRPM = shooterLeftGoalVelRPM;
outputs.shooterRightGoalVelocityRPM = shooterRightGoalVelRPM;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ public void setFF(double kS, double kV, double kA) {
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
public void updateInputs(ShooterInputs inputs) {

inputs.shooterLeftVelocityRPM =
shooterLeft.getVelocity().getValueAsDouble()
Expand All @@ -133,7 +133,7 @@ public void updateInputs(ShooterIOInputs inputs) {
}

@Override
public void applyOutputs(ShooterIOOutputs outputs) {
public void applyOutputs(ShooterOutputs outputs) {
outputs.shooterLeftGoalVelocityRPM = goalLeftVelocityRPM;
outputs.shooterRightGoalVelocityRPM = goalRightVelocityRPM;
outputs.kickerGoalVolts = kickerVolts;
Expand Down

0 comments on commit 7865309

Please sign in to comment.