Skip to content

Commit

Permalink
Setup shooter interface (#8)
Browse files Browse the repository at this point in the history
* Created Shooter Interface

---------

Co-authored-by: Nilesh Agarwalla <[email protected]>
  • Loading branch information
StewardHail3433 and BrownGenius authored Jan 20, 2024
1 parent 4f05fdc commit cb425ba
Show file tree
Hide file tree
Showing 6 changed files with 190 additions and 1 deletion.
27 changes: 26 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,38 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.ShooterEnable;
import frc.robot.subsystems.shooter.ShooterIOSim;
import frc.robot.subsystems.shooter.ShooterSubsystem;

public class RobotContainer {
public final CommandXboxController controller;
public final ShooterSubsystem shooter;

public RobotContainer() {
controller = new CommandXboxController(0);

boolean swerveBot = false;
boolean tankBot = false;

if (swerveBot) {
shooter = null;
} else if (tankBot) {
shooter = null;
} else {
shooter = new ShooterSubsystem(new ShooterIOSim());
}

configureBindings();
}

private void configureBindings() {}
private void configureBindings() {
shooter.setDefaultCommand(new InstantCommand(() -> shooter.disable(), shooter));

controller.rightTrigger().whileTrue(new ShooterEnable(shooter));
}

public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
Expand Down
48 changes: 48 additions & 0 deletions src/main/java/frc/robot/commands/ShooterEnable.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
package frc.robot.commands;

import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.shooter.ShooterSubsystem;
import java.util.Map;

public class ShooterEnable extends Command {
ShooterSubsystem shooter;
ShuffleboardTab tab;
GenericEntry voltsEntry;

public ShooterEnable(ShooterSubsystem shooter) {
this.shooter = shooter;

// create shooter tab on ShuffleBoard
tab = Shuffleboard.getTab("Shooter");
// Create volt entry under Shooter tab as a number sider with min = -1 and max = 1
voltsEntry =
tab.add("Volts", 0)
.withWidget(BuiltInWidgets.kNumberSlider)
.withProperties(Map.of("min", -12, "max", 12))
.getEntry();

// Sets default value to 0.0
voltsEntry.setValue(0.0);

addRequirements(shooter);
}

@Override
public void initialize() {}

@Override
public void execute() {
// Checks the volt Entry for the volt and sets the voltage of motors
shooter.setVoltage(voltsEntry.getDouble(0.0));

// Enable motors, It has to be called regularly for voltage compensation to work properly
shooter.enable();
}

@Override
public void end(boolean interrupted) {}
}
20 changes: 20 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
package frc.robot.subsystems.shooter;

public interface Shooter {
/** Disable the voltage of a motors for the shooter. */
public default void disable() {}

/** Enable the voltage of a motors for the shooter. */
public default void enable() {}

/**
* Set the voltage of motors for the shooter.
*
* @param volts The volts to set. Value should be between -12.0 and 12.0.
*/
public default void setVoltage(double volts) {}

public double getCurrentSpeed();

public double getVoltage();
}
17 changes: 17 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
package frc.robot.subsystems.shooter;

import org.littletonrobotics.junction.AutoLog;

public interface ShooterIO {
@AutoLog
public class ShooterIOInputs {
public double velocityRadPerSec = 0.0;
public double appliedVolts = 0.0;
}

/** Updates the set of loggable inputs. */
public default void updateInputs(ShooterIOInputs inputs) {}

/** Run open loop at the specified voltage. */
public default void setVoltage(double volts) {}
}
27 changes: 27 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.subsystems.shooter;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;

public class ShooterIOSim implements ShooterIO {
private FlywheelSim sim = new FlywheelSim(DCMotor.getNEO(1), 1.5, 0.004);

private double appliedVolts = 0.0;

@Override
public void updateInputs(ShooterIOInputs inputs) {

// Update sim
sim.update(0.02);

// Update inputs
inputs.velocityRadPerSec = sim.getAngularVelocityRadPerSec();
inputs.appliedVolts = appliedVolts;
}

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

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class ShooterSubsystem extends SubsystemBase implements Shooter {
ShooterIO io;
private final ShooterIOInputsAutoLogged inputs = new ShooterIOInputsAutoLogged();
@AutoLogOutput private double voltage;

public ShooterSubsystem(ShooterIO io) {
this.io = io;
voltage = 0;
}

@Override
// Disable the shooter
public void disable() {
voltage = 0;
io.setVoltage(voltage);
}

@Override
// Enable the shooter
public void enable() {
io.setVoltage(voltage);
}

@Override
// Sets the voltage to volts. the volts value is -12 to 12
public void setVoltage(double volts) {
voltage = volts;
}

@Override
public double getVoltage() {
return inputs.appliedVolts;
}

@Override
public double getCurrentSpeed() {
return inputs.velocityRadPerSec;
}

@Override
public void periodic() {
// Updates the inputs
io.updateInputs(inputs);
Logger.processInputs("Shooter", inputs);
}
}

0 comments on commit cb425ba

Please sign in to comment.