shooter code review changes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / Shooter.java
CommitLineData
79ba119a 1package org.usfirst.frc.team3501.robot.subsystems;
2
04227dc0 3import org.usfirst.frc.team3501.robot.Constants;
ac77a7b8 4import org.usfirst.frc.team3501.robot.MathLib;
268b0048 5import org.usfirst.frc.team3501.robot.utils.HallEffectSensor;
04227dc0 6
7import com.ctre.CANTalon;
8
9import edu.wpi.first.wpilibj.command.Subsystem;
10
11public class Shooter extends Subsystem {
1782cbad 12 public double wheelP = 0.0001, wheelI = 0, wheelD = 0.0004;
079a8cb6 13 private static Shooter shooter;
268b0048 14 private static HallEffectSensor hallEffect;
3a86b1a5 15 private final CANTalon flyWheel1, flyWheel2, indexWheel;
79ba119a 16
f625e57a
CZ
17 private static final double DEFAULT_INDEXING_SPEED = -0.75;
18 private static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm
19 private static final double SHOOTING_SPEED_INCREMENT = 25;
ad7e6b1e 20
f625e57a 21 private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
ad7e6b1e 22
079a8cb6 23 private Shooter() {
3a86b1a5
CZ
24 flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
25 flyWheel2 = new CANTalon(Constants.Shooter.FLY_WHEEL2);
04227dc0 26 indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL);
ad7e6b1e 27
268b0048 28 hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
29 }
30
04227dc0 31 /**
32 * Returns shooter object
33 *
34 * @return Shooter object
35 */
079a8cb6
CZ
36 public static Shooter getShooter() {
37 if (shooter == null) {
38 shooter = new Shooter();
39 }
40 return shooter;
41 }
41dfad94 42
079a8cb6 43 /**
04227dc0 44 * Sets fly wheel motor value to input.
45 *
46 * @param val
47 * motor value from -1 to 1(fastest forward)
079a8cb6 48 */
ac77a7b8
CZ
49 public void setFlyWheelMotorVal(double val) {
50 val = MathLib.restrictToRange(val, 0.0, 1.0);
3a86b1a5
CZ
51 flyWheel1.set(val);
52 flyWheel2.set(val);
079a8cb6 53 }
41dfad94 54
04227dc0 55 /**
56 * Stops fly wheel motor.
57 */
58 public void stopFlyWheel() {
3a86b1a5
CZ
59 flyWheel1.set(0);
60 flyWheel2.set(0);
04227dc0 61 }
41dfad94 62
04227dc0 63 /**
64 * Sets index wheel motor value to input.
65 *
66 * @param val
67 * motor value from -1 to 1(fastest forward)
68 */
ac77a7b8
CZ
69 public void setIndexWheelMotorVal(double val) {
70 val = MathLib.restrictToRange(val, -1.0, 1.0);
04227dc0 71 indexWheel.set(val);
079a8cb6 72 }
41dfad94 73
079a8cb6 74 /**
04227dc0 75 * Stops index wheel motor.
079a8cb6
CZ
76 */
77 public void stopIndexWheel() {
04227dc0 78 indexWheel.set(0);
079a8cb6 79 }
41dfad94 80
f625e57a
CZ
81 @Override
82 protected void initDefaultCommand() {
83
84 }
85
86 public double getShooterRPM() {
87 return hallEffect.getRPM();
09e509d3
NA
88 }
89
90 public void setCurrentShootingSpeed(double Value) {
f625e57a 91 currentShootingSpeed = Value;
09e509d3
NA
92 }
93
f625e57a
CZ
94 public void decrementCurrentShootingSpeed() {
95 this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
96 }
079a8cb6 97
f625e57a
CZ
98 public void incrementCurrentShootingSpeed() {
99 this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
079a8cb6 100 }
381dad77 101
f625e57a
CZ
102 public void resetCurrentShootingSpeed() {
103 this.currentShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
104 }
105
106 public double getCurrentShootingSpeed() {
107 return currentShootingSpeed;
108 }
109
110 public void reverseIndexWheel() {
111 this.setIndexWheelMotorVal(-DEFAULT_INDEXING_SPEED);
112 }
113
114 public void runIndexWheel() {
115 this.setIndexWheelMotorVal(DEFAULT_INDEXING_SPEED);
381dad77 116 }
79ba119a 117}