Skip to content

Commit

Permalink
Merge branch 'main' into George-ArmPrototype
Browse files Browse the repository at this point in the history
  • Loading branch information
Steggoo authored Feb 9, 2024
2 parents a5d921d + e21835d commit 1b604c6
Show file tree
Hide file tree
Showing 8 changed files with 419 additions and 107 deletions.
25 changes: 25 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,15 @@ private Constants() {
throw new IllegalStateException("Constants class should not be constructed");
}
public static final Mode currentMode = Mode.PROTO_ARM;
public static final Mode currentMode = Mode.PROTO_SHOOTER;

public enum Mode {
/** Running on a real robot. */
REAL,
PROTO_ARM,

PROTO_SHOOTER,

/** Running a physics simulator. */
SIM,

Expand Down Expand Up @@ -122,6 +125,28 @@ private ArmConstants() {}
public static double SHOULDER_KV = 0.0;
public static double SHOULDER_KG = 0.0;
}
public static class ShooterConstants {
private ShooterConstants() {
throw new IllegalStateException("Static classes should not be constructed");
}
public static final int TOP_LEFT_ID = 13;
public static final int TOP_RIGHT_ID = 14;
public static final int BOTTOM_LEFT_ID = 15;
public static final int BOTTOM_RIGHT_ID = 16;
public static final int KICKER_ID = 17;

public static final double SHOOTER_KP = 0.000061;
public static final double SHOOTER_KI = 0.0;
public static final double SHOOTER_KD = 0.005;
public static final double SHOOTER_KF = 0.000152;

public static final boolean TOP_LEFT_INVERTED = false;
public static final boolean TOP_RIGHT_INVERTED = true;
public static final boolean BOTTOM_LEFT_INVERTED = true;
public static final boolean BOTTOM_RIGHT_INVERTED = false;
public static final boolean KICKER_INVERTED = true;
}

public class ClimberConstants {
private ClimberConstants() {
throw new IllegalStateException("Static class should not be constructed");
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@

package frc.robot;

import com.gos.lib.properties.PropertyManager;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import org.littletonrobotics.junction.LogFileUtil;
Expand All @@ -38,6 +39,8 @@ public class Robot extends LoggedRobot {
*/
@Override
public void robotInit() {
// Clear dead properties
PropertyManager.purgeExtraKeys();
// Record metadata
Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE);
Expand All @@ -60,7 +63,7 @@ public void robotInit() {
// Set up data receivers & replay source
switch (Constants.currentMode) {
case PROTO_ARM:
case REAL:
case REAL, PROTO_SHOOTER:
// Running on a real robot, log to a USB stick ("/U/logs")
Logger.addDataReceiver(new WPILOGWriter());
Logger.addDataReceiver(new NT4Publisher());
Expand Down
17 changes: 12 additions & 5 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,7 @@
import frc.robot.subsystems.drive.module.ModuleIO;
import frc.robot.subsystems.drive.module.ModuleIOSim;
import frc.robot.subsystems.drive.module.ModuleIOTalonFX;
import frc.robot.subsystems.shooter.ShooterIO;
import frc.robot.subsystems.shooter.ShooterIOPrototype;
import frc.robot.subsystems.shooter.ShooterSubsystem;
import frc.robot.subsystems.shooter.*;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

Expand Down Expand Up @@ -92,6 +90,15 @@ public RobotContainer() {
m_shooter = new ShooterSubsystem(new ShooterIO() {});
m_armSubsystem = new ArmSubsystem(new ArmIOPrototype() {});
m_climber = new ClimberSubsystem(new ClimberIOPrototype());
case PROTO_SHOOTER -> {
m_driveSubsystem = new DriveSubsystem(
new GyroIO() {
},
new ModuleIO() {},
new ModuleIO() {},
new ModuleIO() {},
new ModuleIO() {});
m_shooter = new ShooterSubsystem(new ShooterIOPrototype());
}
case SIM -> {
// Sim robot, instantiate physics sim IO implementations
Expand Down Expand Up @@ -166,8 +173,8 @@ private void configureButtonBindings() {
.whileFalse(m_armSubsystem.setWristPowerFactory(0.0));

m_driveSubsystem.setDefaultCommand(
DriveCommands.joystickDrive(
m_driveSubsystem,
DriveCommands.joystickDrive(
m_driveSubsystem,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> -controller.getRightX()));
Expand Down
174 changes: 165 additions & 9 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,22 +5,178 @@
public interface ShooterIO {
@AutoLog
class ShooterIOInputs {
public double topLeftVelocity = 0.0;
public double topRightVelocity = 0.0;
public double bottomLeftVelocity = 0.0;
public double bottomRightVelocity = 0.0;
public double appliedOutput = 0.0;
public double currentDraw = 0.0;
public double temperature = 0.0;
protected double tlVelocityRots = 0.0;
protected double trVelocityRots = 0.0;
protected double blVelocityRots = 0.0;
protected double brVelocityRots = 0.0;
protected double tlAppliedVolts = 0.0;
protected double trAppliedVolts = 0.0;
protected double blAppliedVolts = 0.0;
protected double brAppliedVolts = 0.0;
protected double kickerAppliedVolts = 0.0;
protected double tlCurrentDraw = 0.0;
protected double trCurrentDraw = 0.0;
protected double blCurrentDraw = 0.0;
protected double brCurrentDraw = 0.0;
protected double kickerCurrentDraw = 0.0;
protected double tlTemperature = 0.0;
protected double trTemperature = 0.0;
protected double blTemperature = 0.0;
protected double brTemperature = 0.0;

}

default void updateInput(ShooterIOInputs inputs) {}
public double getTlVelocityRots() {
return tlVelocityRots;
}

public void setTlVelocityRots(double tlVelocityRots) {
this.tlVelocityRots = tlVelocityRots;
}

public double getTrVelocityRots() {
return trVelocityRots;
}

public void setTrVelocityRots(double trVelocityRots) {
this.trVelocityRots = trVelocityRots;
}

public double getBlVelocityRots() {
return blVelocityRots;
}

public void setBlVelocityRots(double blVelocityRots) {
this.blVelocityRots = blVelocityRots;
}

public double getBrVelocityRots() {
return brVelocityRots;
}

public void setBrVelocityRots(double brVelocityRots) {
this.brVelocityRots = brVelocityRots;
}

public double getTlAppliedVolts() {
return tlAppliedVolts;
}

public void setTlAppliedVolts(double tlAppliedVolts) {
this.tlAppliedVolts = tlAppliedVolts;
}

public double getTrAppliedVolts() {
return trAppliedVolts;
}

public void setTrAppliedVolts(double trAppliedVolts) {
this.trAppliedVolts = trAppliedVolts;
}

public double getBlAppliedVolts() {
return blAppliedVolts;
}

public void setBlAppliedVolts(double blAppliedVolts) {
this.blAppliedVolts = blAppliedVolts;
}

public double getBrAppliedVolts() {
return brAppliedVolts;
}

public void setBrAppliedVolts(double brAppliedVolts) {
this.brAppliedVolts = brAppliedVolts;
}

public double getKickerAppliedVolts() {
return kickerAppliedVolts;
}

public void setKickerAppliedVolts(double kickerAppliedVolts) {
this.kickerAppliedVolts = kickerAppliedVolts;
}

public double getTlCurrentDraw() {
return tlCurrentDraw;
}

public void setTlCurrentDraw(double tlCurrentDraw) {
this.tlCurrentDraw = tlCurrentDraw;
}

public double getTrCurrentDraw() {
return trCurrentDraw;
}

public void setTrCurrentDraw(double trCurrentDraw) {
this.trCurrentDraw = trCurrentDraw;
}

public double getBlCurrentDraw() {
return blCurrentDraw;
}

public void setBlCurrentDraw(double blCurrentDraw) {
this.blCurrentDraw = blCurrentDraw;
}

public double getBrCurrentDraw() {
return brCurrentDraw;
}

public void setBrCurrentDraw(double brCurrentDraw) {
this.brCurrentDraw = brCurrentDraw;
}

public double getKickerCurrentDraw() {
return kickerCurrentDraw;
}

public void setKickerCurrentDraw(double kickerCurrentDraw) {
this.kickerCurrentDraw = kickerCurrentDraw;
}

public double getTlTemperature() {
return tlTemperature;
}

public void setTlTemperature(double tlTemperature) {
this.tlTemperature = tlTemperature;
}

public double getTrTemperature() {
return trTemperature;
}

public void setTrTemperature(double trTemperature) {
this.trTemperature = trTemperature;
}

public double getBlTemperature() {
return blTemperature;
}

public void setBlTemperature(double blTemperature) {
this.blTemperature = blTemperature;
}

public double getBrTemperature() {
return brTemperature;
}

public void setBrTemperature(double brTemperature) {
this.brTemperature = brTemperature;
}
}
default void setMotorVoltageTL(double voltage) {}
default void setMotorVoltageTR(double voltage) {}
default void setMotorVoltageBL(double voltage) {}
default void setMotorVoltageBR(double voltage) {}
default void setKickerVoltage(double voltage) {}
default void setIntakeVoltage(double voltage) {}
default void setLeftVelocityRpm(double rpm) {}
default void setRightVelocityRpm(double rpm) {}
default void updateInputs(ShooterIOInputs inputs) {}

}
Loading

0 comments on commit 1b604c6

Please sign in to comment.