-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #91 from Gears-and-Buccaneers/Its-So-Shrimple
Shooter
- Loading branch information
Showing
2 changed files
with
78 additions
and
0 deletions.
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
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); | ||
} | ||
} |