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

Commit

Permalink
feat(shooter): Add simulated hardware.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Jan 8, 2024
1 parent aa8437c commit 44c4be5
Show file tree
Hide file tree
Showing 10 changed files with 296 additions and 8 deletions.
10 changes: 10 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,16 @@
"/FMSInfo": "FMSInfo"
}
},
"NetworkTables": {
"transitory": {
"shooter": {
"beamBreakSensorSim": {
"open": true
},
"open": true
}
}
},
"NetworkTables Info": {
"visible": true
}
Expand Down
18 changes: 18 additions & 0 deletions src/main/java/frc/robot/shooter/BeamBreakSensorIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package frc.robot.shooter;

/** Beam break sensor hardware interface. */
public interface BeamBreakSensorIO {

/** Values for the beam break sensor hardware interface. */
public static class BeamBreakSensorIOValues {
/** If true, the beam break sensor is broken. */
public boolean isBroken = false;
}

/**
* Updates the beam break sensor's values.
*
* @param values
*/
public void update(BeamBreakSensorIOValues values);
}
27 changes: 27 additions & 0 deletions src/main/java/frc/robot/shooter/BeamBreakSensorIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.shooter;

import edu.wpi.first.networktables.BooleanTopic;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import java.util.function.BooleanSupplier;

/** Simulated beam break sensor. */
public class BeamBreakSensorIOSim implements BeamBreakSensorIO {

/** Supplies values for if the beam break sensor is broken. */
private final BooleanSupplier isBrokenSupplier;

/** Creates a simulated beam break sensor. */
public BeamBreakSensorIOSim() {
NetworkTable table = NetworkTableInstance.getDefault().getTable("shooter/beamBreakSensorSim");

BooleanTopic isBrokenTopic = table.getBooleanTopic("isBroken");
isBrokenTopic.publish().set(false);
isBrokenSupplier = isBrokenTopic.subscribe(false);
}

@Override
public void update(BeamBreakSensorIOValues values) {
values.isBroken = isBrokenSupplier.getAsBoolean();
}
}
28 changes: 28 additions & 0 deletions src/main/java/frc/robot/shooter/FlywheelMotorIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
package frc.robot.shooter;

/** Flywheel motor hardware interface. */
public interface FlywheelMotorIO {

/** Values for the flywheel motor hardware interface. */
public static class FlywheelMotorIOValues {
/** Angular velocity of the flywheel in rotations per second. */
public double angularVelocityRotationsPerSecond = 0.0;

/** Current drawn by the flywheel motor in amps. */
public double currentAmps = 0.0;
}

/**
* Updates the flywheel motor's values.
*
* @param values
*/
public void update(FlywheelMotorIOValues values);

/**
* Run the flywheel motor with the specified voltage.
*
* @param volts volts to apply to the flywheel motor.
*/
public void setVoltage(double volts);
}
27 changes: 27 additions & 0 deletions src/main/java/frc/robot/shooter/FlywheelMotorIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.shooter;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import frc.robot.shooter.ShooterConstants.FlywheelConstants;

/** Simulated flywheel motor. */
public class FlywheelMotorIOSim implements FlywheelMotorIO {

/** Represents the motor used the drive the flywheel. */
private final DCMotor motorSim = DCMotor.getNeo550(1);

/** Represents the flywheel driven by the motor. */
private final FlywheelSim flywheelSim =
new FlywheelSim(motorSim, FlywheelConstants.GEARING, FlywheelConstants.MOI);

@Override
public void update(FlywheelMotorIOValues values) {
values.angularVelocityRotationsPerSecond = flywheelSim.getAngularVelocityRPM() / 60.0;
values.currentAmps = flywheelSim.getCurrentDrawAmps();
}

@Override
public void setVoltage(double volts) {
flywheelSim.setInputVoltage(volts);
}
}
28 changes: 28 additions & 0 deletions src/main/java/frc/robot/shooter/SerializerMotorIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
package frc.robot.shooter;

/** Serializer motor hardware interface. */
public interface SerializerMotorIO {

/** Values for the serializer motor hardware interface. */
public static class SerializerMotorIOValues {
/** Angular velocity of the serializer in rotations per second. */
public double angularVelocityRotationsPerSecond = 0.0;

/** Current drawn by the serializer motor in amps. */
public double currentAmps = 0.0;
}

/**
* Updates the serializer motor's values.
*
* @param values
*/
public void update(SerializerMotorIOValues values);

/**
* Run the serializer motor with the specified voltage.
*
* @param volts volts to apply to the serializer motor.
*/
public void setVoltage(double volts);
}
27 changes: 27 additions & 0 deletions src/main/java/frc/robot/shooter/SerializerMotorIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.shooter;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import frc.robot.shooter.ShooterConstants.SerializerConstants;

/** Simulated serializer motor. */
public class SerializerMotorIOSim implements SerializerMotorIO {

/** Represents the motor used the drive the serializer. */
private final DCMotor motorSim = DCMotor.getNeo550(1);

/** Represents the serializer driven by the motor. */
private final FlywheelSim serializerSim =
new FlywheelSim(motorSim, SerializerConstants.GEARING, SerializerConstants.MOI);

@Override
public void update(SerializerMotorIOValues values) {
values.angularVelocityRotationsPerSecond = serializerSim.getAngularVelocityRPM() / 60.0;
values.currentAmps = serializerSim.getCurrentDrawAmps();
}

@Override
public void setVoltage(double volts) {
serializerSim.setInputVoltage(volts);
}
}
74 changes: 69 additions & 5 deletions src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
@@ -1,16 +1,45 @@
package frc.robot.shooter;

import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import frc.lib.Subsystem;
import frc.robot.shooter.BeamBreakSensorIO.BeamBreakSensorIOValues;
import frc.robot.shooter.FlywheelMotorIO.FlywheelMotorIOValues;
import frc.robot.shooter.SerializerMotorIO.SerializerMotorIOValues;
import frc.robot.shooter.ShooterConstants.FlywheelConstants;
import frc.robot.shooter.ShooterConstants.SerializerConstants;

/** The subsystem class for the shooter subsystem. */
/** Subsystem class for the shooter subsystem. */
public class Shooter extends Subsystem {

/** The instance variable for the shooter subsystem singleton. */
/** Instance variable for the shooter subsystem singleton. */
private static Shooter instance = null;

/** Beam break sensor. */
private final BeamBreakSensorIO beamBreakSensor;

/** Beam break sensor values. */
private final BeamBreakSensorIOValues beamBreakSensorValues = new BeamBreakSensorIOValues();

/** Serializer motor. */
private final SerializerMotorIO serializerMotor;

/** Serializer motor values. */
private final SerializerMotorIOValues serializerMotorValues = new SerializerMotorIOValues();

/** Flywheel motor. */
private final FlywheelMotorIO flywheelMotor;

/** Flywheel motor values. */
private final FlywheelMotorIOValues flywheelMotorValues = new FlywheelMotorIOValues();

/** Creates a new instance of the shooter subsystem. */
private Shooter() {}
private Shooter() {
beamBreakSensor = ShooterFactory.createBeamBreakSensor();
serializerMotor = ShooterFactory.createSerializerMotor();
flywheelMotor = ShooterFactory.createFlywheelMotor();
}

/**
* Gets the instance of the shooter subsystem.
Expand All @@ -27,11 +56,46 @@ public static Shooter getInstance() {

@Override
public void periodic() {
// TODO
beamBreakSensor.update(beamBreakSensorValues);
serializerMotor.update(serializerMotorValues);
flywheelMotor.update(flywheelMotorValues);
}

/**
* Calculates the tangential speed of the serializer in meters per second.
*
* @return the tangential speed of the serializer in meters per second.
*/
private double getSerializerTangentialSpeed() {
return serializerMotorValues.angularVelocityRotationsPerSecond * SerializerConstants.RADIUS;
}

/**
* Calculates the tangential speed of the flywheel in meters per second.
*
* @return the tangential speed of the flywheel in meters per second.
*/
private double getFlywheelTangentialSpeed() {
return flywheelMotorValues.angularVelocityRotationsPerSecond * FlywheelConstants.RADIUS;
}

@Override
public void addToShuffleboard(ShuffleboardTab tab) {
// TODO
ShuffleboardLayout sensors =
tab.getLayout("Sensors", BuiltInLayouts.kList).withPosition(0, 0).withSize(2, 4);

sensors.addBoolean("Beam Break Sensor Is Broken?", () -> beamBreakSensorValues.isBroken);

ShuffleboardLayout serializer =
tab.getLayout("Serializer", BuiltInLayouts.kList).withPosition(2, 0).withSize(2, 4);

serializer.addDouble("Serializer Speed (mps)", this::getSerializerTangentialSpeed);
serializer.addDouble("Serializer Current (A)", () -> serializerMotorValues.currentAmps);

ShuffleboardLayout flywheel =
tab.getLayout("Flywheel", BuiltInLayouts.kList).withPosition(4, 0).withSize(2, 4);

flywheel.addDouble("Flywheel Speed (mps)", this::getFlywheelTangentialSpeed);
flywheel.addDouble("Flywheel Current (A)", () -> flywheelMotorValues.currentAmps);
}
}
25 changes: 22 additions & 3 deletions src/main/java/frc/robot/shooter/ShooterConstants.java
Original file line number Diff line number Diff line change
@@ -1,31 +1,50 @@
package frc.robot.shooter;

import edu.wpi.first.math.util.Units;
import frc.lib.CAN;

/** Constants for the shooter subsystem. */
public class ShooterConstants {

/** Constants for the sensors used in the shooter subsystem. */
public static class SensorConstants {
/** The beam break sensor's DIO port number. */
/** Beam break sensor's DIO port number. */
public static final int BEAM_BREAK_PORT = 0; // TODO
}

/** Constants for the serializer motor used in the shooter subsystem. */
public static class SerializerConstants {
/** The serializer motor controller's CAN identifier. */
/** Serializer motor controller's CAN identifier. */
public static final CAN ID = new CAN(0); // TODO

/** If true, invert the serializer motor controller's direction. */
public static final boolean IS_INVERTED = false; // TODO

/** Gearing between the serializer motor and the serializer wheel. */
public static final double GEARING = 1.0; // TODO

/** Moment of interia of the serializer wheel in joules kilograms meters squared. */
public static final double MOI = 0.000125; // TODO

/** Radius of the serializer wheel in meters. */
public static final double RADIUS = 0.5 * Units.inchesToMeters(4.0);
}

/** Constants for the flywheel motor used in the shooter subsystem. */
public static class FlywheelConstants {
/** The flywheel motor controller's CAN identifier. */
/** Flywheel motor controller's CAN identifier. */
public static final CAN ID = new CAN(0); // TODO

/** If true, invert the flywheel motor controller's direction. */
public static final boolean IS_INVERTED = false; // TODO

/** Gearing between the flywheel motor and the flywheel wheel. */
public static final double GEARING = 1.0; // TODO

/** Moment of interia of the flywheel wheel in joules kilograms meters squared. */
public static final double MOI = 0.000125; // TODO

/** Radius of the flywheel wheel in meters. */
public static final double RADIUS = 0.5 * Units.inchesToMeters(4.0);
}
}
40 changes: 40 additions & 0 deletions src/main/java/frc/robot/shooter/ShooterFactory.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package frc.robot.shooter;

import frc.robot.Robot;

/** Helper class for creating hardware for the shooter subsystem. */
public class ShooterFactory {

/**
* Creates a beam break sensor.
*
* @return a beam break sensor.
*/
public static BeamBreakSensorIO createBeamBreakSensor() {
if (Robot.isReal()) return new BeamBreakSensorIOSim(); // TODO

return new BeamBreakSensorIOSim();
}

/**
* Creates a serializer motor.
*
* @return a serializer motor.
*/
public static SerializerMotorIO createSerializerMotor() {
if (Robot.isReal()) return new SerializerMotorIOSim(); // TODO

return new SerializerMotorIOSim();
}

/**
* Creates a flywheel motor.
*
* @return a flywheel motor.
*/
public static FlywheelMotorIO createFlywheelMotor() {
if (Robot.isReal()) return new FlywheelMotorIOSim(); // TODO

return new FlywheelMotorIOSim();
}
}

0 comments on commit 44c4be5

Please sign in to comment.