Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
feat(shooter): Implement working serializer simulation.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Jan 8, 2024
1 parent 44c4be5 commit 9d50092
Show file tree
Hide file tree
Showing 5 changed files with 47 additions and 1 deletion.
7 changes: 7 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
Expand Up @@ -88,5 +88,12 @@
"buttonCount": 0,
"povCount": 0
}
],
"robotJoysticks": [
{},
{
"guid": "78696e70757401000000000000000000",
"useGamepad": true
}
]
}
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@ private void initializeShuffleboards() {

private void configureBindings() {
// TODO
operator.rightBumper().whileTrue(shooter.serialize()).onFalse(shooter.stopSerializing());
operator.rightTrigger().whileTrue(shooter.smartSerialize()).onFalse(shooter.stopSerializing());
}

public Command getAutonomousCommand() {
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/shooter/FlywheelMotorIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ public class FlywheelMotorIOSim implements FlywheelMotorIO {

@Override
public void update(FlywheelMotorIOValues values) {
flywheelSim.update(0.02);
values.angularVelocityRotationsPerSecond = flywheelSim.getAngularVelocityRPM() / 60.0;
values.currentAmps = flywheelSim.getCurrentDrawAmps();
}
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/shooter/SerializerMotorIOSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ public class SerializerMotorIOSim implements SerializerMotorIO {

@Override
public void update(SerializerMotorIOValues values) {
serializerSim.update(0.02);
values.angularVelocityRotationsPerSecond = serializerSim.getAngularVelocityRPM() / 60.0;
values.currentAmps = serializerSim.getCurrentDrawAmps();
}
Expand Down
37 changes: 36 additions & 1 deletion src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.lib.Subsystem;
import frc.robot.shooter.BeamBreakSensorIO.BeamBreakSensorIOValues;
import frc.robot.shooter.FlywheelMotorIO.FlywheelMotorIOValues;
Expand Down Expand Up @@ -61,6 +63,24 @@ public void periodic() {
flywheelMotor.update(flywheelMotorValues);
}

/**
* Returns true if the shooter is holding a note.
*
* @return true if the shooter is holding a note.
*/
private boolean isHoldingNote() {
return beamBreakSensorValues.isBroken; // TODO debounce / filter?
}

/**
* Returns true if the shooter is not holding a note.
*
* @return true if the shooter is not holding a note.
*/
private boolean isNotHoldingNote() {
return !isHoldingNote();
}

/**
* Calculates the tangential speed of the serializer in meters per second.
*
Expand All @@ -84,7 +104,7 @@ public void addToShuffleboard(ShuffleboardTab tab) {
ShuffleboardLayout sensors =
tab.getLayout("Sensors", BuiltInLayouts.kList).withPosition(0, 0).withSize(2, 4);

sensors.addBoolean("Beam Break Sensor Is Broken?", () -> beamBreakSensorValues.isBroken);
sensors.addBoolean("Is Holding Note?", this::isHoldingNote);

ShuffleboardLayout serializer =
tab.getLayout("Serializer", BuiltInLayouts.kList).withPosition(2, 0).withSize(2, 4);
Expand All @@ -98,4 +118,19 @@ public void addToShuffleboard(ShuffleboardTab tab) {
flywheel.addDouble("Flywheel Speed (mps)", this::getFlywheelTangentialSpeed);
flywheel.addDouble("Flywheel Current (A)", () -> flywheelMotorValues.currentAmps);
}

public Command serialize() {
return Commands.run(() -> serializerMotor.setVoltage(4));
}

public Command stopSerializing() {
return Commands.runOnce(() -> serializerMotor.setVoltage(0));
}

public Command smartSerialize() {
return serialize()
.until(this::isNotHoldingNote)
.unless(this::isNotHoldingNote)
.andThen(stopSerializing());
}
}

0 comments on commit 9d50092

Please sign in to comment.