-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge remote-tracking branch 'origin/staging' into elevator
- Loading branch information
Showing
7 changed files
with
296 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
30 changes: 30 additions & 0 deletions
30
src/main/java/org/team1540/robot2024/commands/indexer/IntakeCommand.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,30 @@ | ||
package org.team1540.robot2024.commands.indexer; | ||
|
||
import edu.wpi.first.wpilibj2.command.Command; | ||
import org.team1540.robot2024.subsystems.indexer.Indexer; | ||
|
||
public class IntakeCommand extends Command { | ||
|
||
private final Indexer indexer; | ||
|
||
public IntakeCommand(Indexer indexer) { | ||
this.indexer = indexer; | ||
addRequirements(indexer); | ||
} | ||
|
||
@Override | ||
public void initialize() { | ||
indexer.setIntakePercent(0.4); | ||
} | ||
|
||
|
||
@Override | ||
public boolean isFinished() { | ||
return indexer.isNotePresent(); | ||
} | ||
|
||
@Override | ||
public void end(boolean interrupted) { | ||
indexer.setIntakePercent(0); | ||
} | ||
} |
51 changes: 51 additions & 0 deletions
51
src/main/java/org/team1540/robot2024/subsystems/indexer/Indexer.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,51 @@ | ||
package org.team1540.robot2024.subsystems.indexer; | ||
|
||
import edu.wpi.first.wpilibj2.command.Command; | ||
import edu.wpi.first.wpilibj2.command.Commands; | ||
import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
import org.littletonrobotics.junction.Logger; | ||
import org.team1540.robot2024.util.LoggedTunableNumber; | ||
import static org.team1540.robot2024.Constants.Indexer.*; | ||
import static org.team1540.robot2024.Constants.tuningMode; | ||
|
||
|
||
public class Indexer extends SubsystemBase { | ||
private final IndexerIO indexerIO; | ||
private final IndexerIOInputsAutoLogged indexerInputs = new IndexerIOInputsAutoLogged(); | ||
private final LoggedTunableNumber kP = new LoggedTunableNumber("Indexer/kP", FEEDER_KP); | ||
private final LoggedTunableNumber kI = new LoggedTunableNumber("Indexer/kI", FEEDER_KI); | ||
private final LoggedTunableNumber kD = new LoggedTunableNumber("Indexer/kD", FEEDER_KD); | ||
|
||
|
||
public Indexer(IndexerIO indexerIO) { | ||
this.indexerIO = indexerIO; | ||
} | ||
|
||
public void periodic() { | ||
indexerIO.updateInputs(indexerInputs); | ||
Logger.processInputs("Indexer", indexerInputs); | ||
if (tuningMode) { | ||
if (kP.hasChanged(hashCode()) || kI.hasChanged(hashCode()) || kD.hasChanged(hashCode())) { | ||
indexerIO.configureFeederPID(kP.get(), kI.get(), kD.get()); | ||
} | ||
} | ||
} | ||
|
||
public void setIntakePercent(double percent) { | ||
indexerIO.setIntakeVoltage(percent * 12.0); | ||
} | ||
|
||
public boolean isNotePresent() { | ||
return indexerInputs.noteInIntake; | ||
} | ||
|
||
public Command feedToAmp() { | ||
return Commands.runOnce(() -> indexerIO.setFeederVelocity(-600), this); | ||
} | ||
|
||
public Command feedToShooter() { | ||
return Commands.runOnce(() -> indexerIO.setFeederVelocity(1200), this); | ||
} | ||
|
||
|
||
} |
33 changes: 33 additions & 0 deletions
33
src/main/java/org/team1540/robot2024/subsystems/indexer/IndexerIO.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,33 @@ | ||
package org.team1540.robot2024.subsystems.indexer; | ||
|
||
import org.littletonrobotics.junction.AutoLog; | ||
|
||
public interface IndexerIO { | ||
|
||
@AutoLog | ||
class IndexerIOInputs { | ||
public double intakeVoltage; | ||
public double intakeCurrentAmps; | ||
public double intakeVelocityRPM; | ||
public double feederVoltage; | ||
public double feederCurrentAmps; | ||
public double feederVelocityRPM; | ||
public boolean noteInIntake = false; | ||
public double setpointRPM; | ||
public double feederVelocityError; | ||
} | ||
|
||
/** | ||
* Updates the set of loggable inputs. | ||
*/ | ||
default void updateInputs(IndexerIOInputs inputs) {} | ||
|
||
default void setIntakeVoltage(double volts) {} | ||
|
||
default void setFeederVoltage(double volts) {} | ||
|
||
default void setFeederVelocity(double velocity) {} | ||
|
||
default void configureFeederPID(double p, double i, double d) {} | ||
|
||
} |
66 changes: 66 additions & 0 deletions
66
src/main/java/org/team1540/robot2024/subsystems/indexer/IndexerIOSim.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,66 @@ | ||
package org.team1540.robot2024.subsystems.indexer; | ||
|
||
import edu.wpi.first.math.MathUtil; | ||
import edu.wpi.first.math.controller.PIDController; | ||
import edu.wpi.first.math.system.plant.DCMotor; | ||
import edu.wpi.first.wpilibj.simulation.DCMotorSim; | ||
import edu.wpi.first.wpilibj.simulation.SimDeviceSim; | ||
import org.team1540.robot2024.Constants; | ||
|
||
import static org.team1540.robot2024.Constants.Indexer.*; | ||
|
||
public class IndexerIOSim implements IndexerIO { | ||
|
||
|
||
private final DCMotorSim intakeSim = new DCMotorSim(DCMotor.getNEO(1), INTAKE_GEAR_RATIO, INTAKE_MOI); | ||
private final DCMotorSim feederSim = new DCMotorSim(DCMotor.getNEO(1), FEEDER_GEAR_RATIO, FEEDER_MOI); | ||
// private final SimDeviceSim beamBreakSim = new SimDeviceSim("Indexer Beam Break"); | ||
private final PIDController feederSimPID = new PIDController(FEEDER_KP, FEEDER_KI,FEEDER_KD); | ||
private boolean isClosedLoop = true; | ||
private double intakeVoltage = 0.0; | ||
private double feederVoltage = 0.0; | ||
private double feederSetpointRPS = 0.0; | ||
|
||
@Override | ||
public void updateInputs(IndexerIOInputs inputs) { | ||
if (isClosedLoop) { | ||
feederVoltage = MathUtil.clamp(feederSimPID.calculate(feederSim.getAngularVelocityRPM() / 60, feederSetpointRPS), -12.0, 12.0); | ||
} | ||
intakeSim.setInputVoltage(intakeVoltage); | ||
feederSim.setInputVoltage(feederVoltage); | ||
intakeSim.update(Constants.LOOP_PERIOD_SECS); | ||
feederSim.update(Constants.LOOP_PERIOD_SECS); | ||
inputs.intakeCurrentAmps = intakeSim.getCurrentDrawAmps(); | ||
inputs.intakeVoltage = intakeVoltage; | ||
inputs.intakeVelocityRPM = intakeSim.getAngularVelocityRPM(); | ||
inputs.feederCurrentAmps = feederSim.getCurrentDrawAmps(); | ||
inputs.feederVoltage = feederVoltage; | ||
inputs.feederVelocityRPM = feederSim.getAngularVelocityRPM(); | ||
// inputs.noteInIntake = beamBreakSim.getBoolean("Indexer Beam Break").get(); | ||
inputs.setpointRPM = feederSimPID.getSetpoint() * 60; | ||
inputs.feederVelocityError = feederSimPID.getPositionError(); | ||
} | ||
|
||
@Override | ||
public void setIntakeVoltage(double volts) { | ||
intakeVoltage = MathUtil.clamp(volts, -12.0, 12.0); | ||
} | ||
|
||
@Override | ||
public void configureFeederPID(double p, double i, double d) { | ||
feederSimPID.setPID(p, i, d); | ||
} | ||
|
||
public void setFeederVoltage(double volts) { | ||
isClosedLoop = false; | ||
feederVoltage = MathUtil.clamp(volts, -12.0, 12.0); | ||
} | ||
|
||
|
||
public void setFeederVelocity(double velocity) { | ||
isClosedLoop = true; | ||
feederSimPID.reset(); | ||
feederSetpointRPS = velocity / 60; | ||
} | ||
|
||
} |
75 changes: 75 additions & 0 deletions
75
src/main/java/org/team1540/robot2024/subsystems/indexer/IndexerIOSparkMax.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,75 @@ | ||
package org.team1540.robot2024.subsystems.indexer; | ||
|
||
import com.revrobotics.*; | ||
import edu.wpi.first.math.controller.SimpleMotorFeedforward; | ||
import edu.wpi.first.wpilibj.DigitalInput; | ||
|
||
import static org.team1540.robot2024.Constants.Indexer.*; | ||
|
||
|
||
public class IndexerIOSparkMax implements IndexerIO { | ||
private final CANSparkMax intakeMotor = new CANSparkMax(INTAKE_ID, CANSparkLowLevel.MotorType.kBrushless); | ||
private final CANSparkMax feederMotor = new CANSparkMax(FEEDER_ID, CANSparkLowLevel.MotorType.kBrushless); | ||
private final DigitalInput indexerBeamBreak = new DigitalInput(BEAM_BREAK_ID); | ||
private final SparkPIDController feederPID; | ||
private final SimpleMotorFeedforward feederFF = new SimpleMotorFeedforward(FEEDER_KS, FEEDER_KV); | ||
private double setpointRPM; | ||
|
||
|
||
public IndexerIOSparkMax() { | ||
intakeMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); | ||
intakeMotor.enableVoltageCompensation(12.0); | ||
intakeMotor.setSmartCurrentLimit(30); | ||
|
||
feederMotor.setIdleMode(CANSparkBase.IdleMode.kBrake); | ||
feederMotor.enableVoltageCompensation(12.0); | ||
feederMotor.setSmartCurrentLimit(30); | ||
|
||
feederPID = feederMotor.getPIDController(); | ||
feederPID.setP(FEEDER_KP, 0); | ||
feederPID.setI(FEEDER_KI, 0); | ||
feederPID.setD(FEEDER_KD, 0); | ||
} | ||
|
||
@Override | ||
public void updateInputs(IndexerIOInputs inputs) { | ||
inputs.intakeCurrentAmps = intakeMotor.getOutputCurrent(); | ||
inputs.intakeVoltage = intakeMotor.getBusVoltage() * intakeMotor.getAppliedOutput(); | ||
inputs.intakeVelocityRPM = intakeMotor.getEncoder().getVelocity(); | ||
inputs.feederCurrentAmps = feederMotor.getOutputCurrent(); | ||
inputs.feederVoltage = feederMotor.getBusVoltage() * feederMotor.getAppliedOutput(); | ||
inputs.feederVelocityRPM = feederMotor.getEncoder().getVelocity(); | ||
inputs.noteInIntake = indexerBeamBreak.get(); | ||
inputs.setpointRPM = setpointRPM; | ||
inputs.feederVelocityError = setpointRPM - feederMotor.getEncoder().getVelocity(); | ||
} | ||
|
||
@Override | ||
public void setIntakeVoltage(double volts) { | ||
intakeMotor.setVoltage(volts); | ||
} | ||
|
||
@Override | ||
public void setFeederVoltage(double volts) { | ||
feederMotor.setVoltage(volts); | ||
} | ||
|
||
@Override | ||
public void setFeederVelocity(double velocity) { | ||
setpointRPM = velocity; | ||
feederPID.setReference( | ||
velocity / FEEDER_GEAR_RATIO, // Should this be multiplied? | ||
CANSparkBase.ControlType.kVelocity, | ||
0, | ||
feederFF.calculate(velocity), | ||
SparkPIDController.ArbFFUnits.kVoltage | ||
); | ||
} | ||
|
||
@Override | ||
public void configureFeederPID(double p, double i, double d) { | ||
feederPID.setP(p); | ||
feederPID.setI(i); | ||
feederPID.setD(d); | ||
} | ||
} |