Skip to content

Commit

Permalink
Added feeder to indexer
Browse files Browse the repository at this point in the history
  • Loading branch information
keckothedragon committed May 17, 2024
1 parent cdff8b2 commit a7debc4
Show file tree
Hide file tree
Showing 10 changed files with 116 additions and 42 deletions.
Binary file modified ctre_sim/Pigeon 2 - 020 - 0 - ext.dat
Binary file not shown.
17 changes: 13 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,10 @@ private void configureSubsystems() {
m_indexer =
new Indexer(
new IndexerIOFalcon(
Ports.kKicker, Ports.kIndexerBeamBreakOne, Ports.kIndexerBeamBreakTwo));
Ports.kKicker,
Ports.kFeeder,
Ports.kIndexerBeamBreakOne,
Ports.kIndexerBeamBreakTwo));
} else {
m_drive =
new Drive(
Expand All @@ -106,6 +109,7 @@ private void configureSubsystems() {
}

private void configureControllers() {
// usually use ps5 on actual robot but xbox is better for keyboard testing
if (RobotBase.isReal()) {
m_driverControls = new DriverControlsPS5(1);
} else {
Expand Down Expand Up @@ -137,9 +141,14 @@ private void configureButtonBindings() {
}));

m_driverControls
.testIndexer()
.onTrue(m_indexer.runIndexer(6.0))
.onFalse(m_indexer.runIndexer(0.0));
.testKicker()
.onTrue(m_indexer.runKicker(6.0))
.onFalse(m_indexer.runKicker(0.0));

m_driverControls
.testFeeder()
.onTrue(m_indexer.runFeeder(6.0))
.onFalse(m_indexer.runFeeder(0.0));
}

public void updateRobotState() {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -85,15 +85,15 @@ public static RobotState getInstance() {
public void updateMechanism() {
m_shooterPivotMechLower.setAngle(m_shooter.getPivotAngle().getDegrees() + 180);
m_shooterPivotMechUpper.setAngle(m_shooter.getPivotAngle().getDegrees());

Logger.recordOutput("Mechanism", m_mechanism);
}

public void updateComponents() {
Pose3d shooterPose =
new Pose3d(
kShooterZeroTranslation, new Rotation3d(0, -m_shooter.getPivotAngle().getRadians(), 0));

Logger.recordOutput("Mechanism", m_mechanism);

Logger.recordOutput("Components/ShooterPose", shooterPose);
Logger.recordOutput("Components/ZeroPose", new Pose3d()); // for tuning config
}
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/oi/DriverControls.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,5 +11,7 @@ public interface DriverControls {

public Trigger testShooter();

public Trigger testIndexer();
public Trigger testKicker();

public Trigger testFeeder();
}
9 changes: 7 additions & 2 deletions src/main/java/frc/robot/oi/DriverControlsPS5.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,12 @@ public Trigger testShooter() {
}

@Override
public Trigger testIndexer() {
return m_controller.R2();
public Trigger testKicker() {
return m_controller.R1();
}

@Override
public Trigger testFeeder() {
return m_controller.L1();
}
}
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/oi/DriverControlsXbox.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,12 @@ public Trigger testShooter() {
}

@Override
public Trigger testIndexer() {
public Trigger testKicker() {
return m_controller.button(2);
}

@Override
public Trigger testFeeder() {
return m_controller.button(3);
}
}
8 changes: 6 additions & 2 deletions src/main/java/frc/robot/subsystems/indexer/Indexer.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,11 @@ public void periodic() {
Logger.processInputs("Indexer", m_inputs);
}

public Command runIndexer(double voltage) {
return Commands.runOnce(() -> m_io.setVoltage(voltage));
public Command runKicker(double voltage) {
return Commands.runOnce(() -> m_io.setKickerVoltage(voltage));
}

public Command runFeeder(double voltage) {
return Commands.runOnce(() -> m_io.setFeederVoltage(voltage));
}
}
13 changes: 9 additions & 4 deletions src/main/java/frc/robot/subsystems/indexer/IndexerIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,17 @@
public interface IndexerIO extends LoggedIO<IndexerIO.IndexerInputs> {
@AutoLog
public static class IndexerInputs {
public double curVelocity;
public double curVoltage;
public double curAmps;
public double curKickerVelocity;
public double curKickerVoltage;
public double curKickerAmps;
public double curFeederVelocity;
public double curFeederVoltage;
public double curFeederAmps;
public boolean beamBreakOneBroken;
public boolean beamBreakTwoBroken;
}

public void setVoltage(double voltage);
public void setKickerVoltage(double voltage);

public void setFeederVoltage(double voltage);
}
56 changes: 41 additions & 15 deletions src/main/java/frc/robot/subsystems/indexer/IndexerIOFalcon.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,37 +7,63 @@
import edu.wpi.first.wpilibj.DigitalInput;

public class IndexerIOFalcon implements IndexerIO {
private TalonFX m_indexerMotor;
private TalonFX m_kickerMotor;
private TalonFX m_feederMotor;
private DigitalInput m_beamBreakOne;
private DigitalInput m_beamBreakTwo;

private StatusSignal<Double> m_curVelocity;
private StatusSignal<Double> m_curVoltage;
private StatusSignal<Double> m_curAmps;
private StatusSignal<Double> m_curKickerVelocity;
private StatusSignal<Double> m_curKickerVoltage;
private StatusSignal<Double> m_curKickerAmps;
private StatusSignal<Double> m_curFeederVelocity;
private StatusSignal<Double> m_curFeederVoltage;
private StatusSignal<Double> m_curFeederAmps;

public IndexerIOFalcon(int motorPort, int beamBreakOnePort, int beamBreakTwoPort) {
m_indexerMotor = new TalonFX(motorPort);
public IndexerIOFalcon(
int kickerPort, int feederPort, int beamBreakOnePort, int beamBreakTwoPort) {
m_kickerMotor = new TalonFX(kickerPort);
m_feederMotor = new TalonFX(feederPort);
m_beamBreakOne = new DigitalInput(beamBreakOnePort);
m_beamBreakTwo = new DigitalInput(beamBreakTwoPort);

m_curVelocity = m_indexerMotor.getVelocity();
m_curVoltage = m_indexerMotor.getMotorVoltage();
m_curAmps = m_indexerMotor.getSupplyCurrent();
m_curKickerVelocity = m_kickerMotor.getVelocity();
m_curKickerVoltage = m_kickerMotor.getMotorVoltage();
m_curKickerAmps = m_kickerMotor.getSupplyCurrent();

m_curFeederVelocity = m_feederMotor.getVelocity();
m_curFeederVoltage = m_feederMotor.getMotorVoltage();
m_curFeederAmps = m_feederMotor.getSupplyCurrent();
}

@Override
public void updateInputs(IndexerInputs inputs) {
BaseStatusSignal.refreshAll(m_curVelocity, m_curVoltage, m_curAmps);
BaseStatusSignal.refreshAll(
m_curKickerVelocity,
m_curKickerVoltage,
m_curKickerAmps,
m_curFeederVelocity,
m_curFeederVoltage,
m_curFeederAmps);

inputs.curKickerVelocity = Units.rotationsToRadians(m_curKickerVelocity.getValue());
inputs.curKickerVoltage = m_curKickerVoltage.getValue();
inputs.curKickerAmps = m_curKickerAmps.getValue();

inputs.curFeederVelocity = Units.rotationsToRadians(m_curFeederVelocity.getValue());
inputs.curFeederVoltage = m_curFeederVoltage.getValue();
inputs.curFeederAmps = m_curFeederAmps.getValue();

inputs.curVelocity = Units.rotationsToRadians(m_curVelocity.getValue());
inputs.curVoltage = m_curVoltage.getValue();
inputs.curAmps = m_curAmps.getValue();
inputs.beamBreakOneBroken = m_beamBreakOne.get();
inputs.beamBreakTwoBroken = m_beamBreakTwo.get();
}

@Override
public void setVoltage(double voltage) {
m_indexerMotor.setVoltage(voltage);
public void setKickerVoltage(double voltage) {
m_kickerMotor.setVoltage(voltage);
}

@Override
public void setFeederVoltage(double voltage) {
m_feederMotor.setVoltage(voltage);
}
}
40 changes: 29 additions & 11 deletions src/main/java/frc/robot/subsystems/indexer/IndexerIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,34 +6,52 @@
import frc.robot.Constants.Ports;

public class IndexerIOSim implements IndexerIO {
private DCMotorSim m_motorSim;
private double m_curVoltage;
private DCMotorSim m_kickerSim;
private DCMotorSim m_feederSim;
private double m_curKickerVoltage;
private double m_curFeederVoltage;
private DIOSim m_beamBreakOne;
private DIOSim m_beamBreakTwo;

public IndexerIOSim() {
double simGearing = 1.0;
double simJkGMetersSquared = 1.0;
m_motorSim = new DCMotorSim(DCMotor.getFalcon500(1), simGearing, simJkGMetersSquared);
double simJkGMetersSquared = 0.01;
m_kickerSim = new DCMotorSim(DCMotor.getFalcon500(1), simGearing, simJkGMetersSquared);
m_feederSim = new DCMotorSim(DCMotor.getFalcon500(1), simGearing, simJkGMetersSquared);

m_beamBreakOne = new DIOSim(Ports.kIndexerBeamBreakOne);
m_beamBreakTwo = new DIOSim(Ports.kIndexerBeamBreakTwo);

m_curKickerVoltage = 0.0;
m_curFeederVoltage = 0.0;
}

@Override
public void updateInputs(IndexerInputs inputs) {
m_motorSim.update(0.02);
m_kickerSim.update(0.02);
m_feederSim.update(0.02);

inputs.curKickerVoltage = m_curKickerVoltage;
inputs.curKickerVelocity = m_kickerSim.getAngularVelocityRadPerSec();
inputs.curKickerAmps = m_kickerSim.getCurrentDrawAmps();

inputs.curFeederVoltage = m_curFeederVoltage;
inputs.curFeederVelocity = m_feederSim.getAngularVelocityRadPerSec();
inputs.curFeederAmps = m_feederSim.getCurrentDrawAmps();

inputs.curVoltage = m_curVoltage;
inputs.curVelocity = m_motorSim.getAngularVelocityRadPerSec();
inputs.curAmps = m_motorSim.getCurrentDrawAmps();
inputs.beamBreakOneBroken = m_beamBreakOne.getValue();
inputs.beamBreakTwoBroken = m_beamBreakTwo.getValue();
}

@Override
public void setVoltage(double voltage) {
m_motorSim.setInputVoltage(voltage);
m_curVoltage = voltage;
public void setKickerVoltage(double voltage) {
m_kickerSim.setInputVoltage(voltage);
m_curKickerVoltage = voltage;
}

@Override
public void setFeederVoltage(double voltage) {
m_feederSim.setInputVoltage(voltage);
m_curFeederVoltage = voltage;
}
}

0 comments on commit a7debc4

Please sign in to comment.