Skip to content

Commit

Permalink
Merge pull request #91 from Gears-and-Buccaneers/Its-So-Shrimple
Browse files Browse the repository at this point in the history
Shooter
  • Loading branch information
dspeyrer authored Nov 21, 2024
2 parents 4824858 + 624dedf commit ce9b369
Show file tree
Hide file tree
Showing 2 changed files with 78 additions and 0 deletions.
2 changes: 2 additions & 0 deletions src/main/java/frc/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ public class Robot extends TimedRobot {
// Subsystems
private final Swerve drivetrain = SwerveConfig.swerve;
private final Intake intake = new Intake();
private final Shooter shooterLeft = new Shooter(15);
private final Shooter shooterRight = new Shooter(16);

// Utilities
static double squareInput(double input) {
Expand Down
76 changes: 76 additions & 0 deletions src/main/java/frc/system/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
package frc.system;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.SupplyCurrentLimitConfiguration;
import com.ctre.phoenix.motorcontrol.TalonSRXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem;

public class Shooter implements Subsystem {
// Hardware
private final TalonSRX shooterMotor;

private double defaultShooterSpeed = .8;

public Shooter(int id) {
// Motor
shooterMotor = new TalonSRX(id);

// Configs
shooterMotor.setInverted(false);

shooterMotor.setNeutralMode(NeutralMode.Coast);

SupplyCurrentLimitConfiguration currentLimits = new SupplyCurrentLimitConfiguration();

currentLimits.currentLimit = 40;
currentLimits.enable = true;

shooterMotor.configSupplyCurrentLimit(currentLimits);

register();
}

private Command feed(boolean forwards, double percentMaxSpeed) {
Command cmd = new Command() {
public void initialize() {
double speed = forwards ? defaultShooterSpeed : -defaultShooterSpeed;
speed *= percentMaxSpeed;

shooterMotor.set(TalonSRXControlMode.PercentOutput, speed);
}

public void end(boolean interrupted) {
disable();
}
};

cmd.addRequirements(this);

return cmd;
}

private void disable() {
shooterMotor.set(TalonSRXControlMode.Disabled, 0);
}

/**
* returns a command that runs the Shooter FORWARD
* when it ends it disables the Shooter
* Shooter command requires itself
*/
public Command runIn() {
return feed(true, 1);
}

/**
* returns a command that runs the Shooter SLOWER
* when it ends it disables the Shooter
* Shooter command requires itself
*/
public Command runOut() {
return feed(true, .8);
}
}

0 comments on commit ce9b369

Please sign in to comment.