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