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; |
7ba6bc91 | 6 | import org.usfirst.frc.team3501.robot.utils.PIDController; |
04227dc0 | 7 | |
8 | import com.ctre.CANTalon; | |
9 | ||
185e0c8d RR |
10 | import edu.wpi.first.wpilibj.DoubleSolenoid; |
11 | import edu.wpi.first.wpilibj.DoubleSolenoid.Value; | |
04227dc0 | 12 | import edu.wpi.first.wpilibj.command.Subsystem; |
13 | ||
14 | public class Shooter extends Subsystem { | |
7ba6bc91 | 15 | public double wheelP = 0.00007, wheelI = 0, wheelD = 0.0008; |
079a8cb6 | 16 | private static Shooter shooter; |
268b0048 | 17 | private static HallEffectSensor hallEffect; |
3a86b1a5 | 18 | private final CANTalon flyWheel1, flyWheel2, indexWheel; |
79ba119a | 19 | |
7ba6bc91 CZ |
20 | private PIDController wheelController; |
21 | ||
22 | private static final double RPM_THRESHOLD = 10; | |
cb8e86cb CZ |
23 | private static final double DEFAULT_INDEXING_MOTOR_VALUE = -0.75; |
24 | private static final double DEFAULT_SHOOTING_SPEED = 3100; // rpm | |
f56e6ebf | 25 | private static final double SHOOTING_SPEED_INCREMENT = 50; |
ad7e6b1e | 26 | |
7ba6bc91 CZ |
27 | private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED; |
28 | private double currentShooterMotorValue = 0; | |
ad7e6b1e | 29 | |
185e0c8d RR |
30 | private final DoubleSolenoid piston; |
31 | ||
079a8cb6 | 32 | private Shooter() { |
3a86b1a5 CZ |
33 | flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1); |
34 | flyWheel2 = new CANTalon(Constants.Shooter.FLY_WHEEL2); | |
04227dc0 | 35 | indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL); |
ad7e6b1e | 36 | |
268b0048 | 37 | hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1); |
185e0c8d | 38 | |
82fa994f | 39 | piston = new DoubleSolenoid(Constants.Shooter.MODULE_NUMBER, |
185e0c8d | 40 | Constants.Shooter.PISTON_FORWARD, Constants.Shooter.PISTON_REVERSE); |
268b0048 | 41 | } |
42 | ||
04227dc0 | 43 | /** |
44 | * Returns shooter object | |
45 | * | |
46 | * @return Shooter object | |
47 | */ | |
079a8cb6 CZ |
48 | public static Shooter getShooter() { |
49 | if (shooter == null) { | |
50 | shooter = new Shooter(); | |
51 | } | |
52 | return shooter; | |
53 | } | |
41dfad94 | 54 | |
079a8cb6 | 55 | /** |
04227dc0 | 56 | * Sets fly wheel motor value to input. |
57 | * | |
58 | * @param val | |
59 | * motor value from -1 to 1(fastest forward) | |
079a8cb6 | 60 | */ |
ac77a7b8 CZ |
61 | public void setFlyWheelMotorVal(double val) { |
62 | val = MathLib.restrictToRange(val, 0.0, 1.0); | |
3a86b1a5 CZ |
63 | flyWheel1.set(val); |
64 | flyWheel2.set(val); | |
079a8cb6 | 65 | } |
41dfad94 | 66 | |
04227dc0 | 67 | /** |
68 | * Stops fly wheel motor. | |
69 | */ | |
70 | public void stopFlyWheel() { | |
3a86b1a5 CZ |
71 | flyWheel1.set(0); |
72 | flyWheel2.set(0); | |
04227dc0 | 73 | } |
41dfad94 | 74 | |
04227dc0 | 75 | /** |
76 | * Sets index wheel motor value to input. | |
77 | * | |
78 | * @param val | |
79 | * motor value from -1 to 1(fastest forward) | |
80 | */ | |
ac77a7b8 CZ |
81 | public void setIndexWheelMotorVal(double val) { |
82 | val = MathLib.restrictToRange(val, -1.0, 1.0); | |
04227dc0 | 83 | indexWheel.set(val); |
079a8cb6 | 84 | } |
41dfad94 | 85 | |
079a8cb6 | 86 | /** |
04227dc0 | 87 | * Stops index wheel motor. |
079a8cb6 CZ |
88 | */ |
89 | public void stopIndexWheel() { | |
04227dc0 | 90 | indexWheel.set(0); |
079a8cb6 | 91 | } |
41dfad94 | 92 | |
f625e57a CZ |
93 | @Override |
94 | protected void initDefaultCommand() { | |
95 | ||
96 | } | |
97 | ||
7ba6bc91 CZ |
98 | public double getRPMThreshold() { |
99 | return RPM_THRESHOLD; | |
100 | } | |
101 | ||
f625e57a CZ |
102 | public double getShooterRPM() { |
103 | return hallEffect.getRPM(); | |
09e509d3 NA |
104 | } |
105 | ||
7ba6bc91 CZ |
106 | public void setTargetShootingSpeed(double Value) { |
107 | targetShootingSpeed = Value; | |
09e509d3 NA |
108 | } |
109 | ||
7ba6bc91 CZ |
110 | public void decrementTargetShootingSpeed() { |
111 | this.targetShootingSpeed -= this.SHOOTING_SPEED_INCREMENT; | |
f625e57a | 112 | } |
079a8cb6 | 113 | |
7ba6bc91 CZ |
114 | public void incrementTargetShootingSpeed() { |
115 | this.targetShootingSpeed += this.SHOOTING_SPEED_INCREMENT; | |
079a8cb6 | 116 | } |
381dad77 | 117 | |
7ba6bc91 CZ |
118 | public void resetTargetShootingSpeed() { |
119 | this.targetShootingSpeed = this.DEFAULT_SHOOTING_SPEED; | |
f625e57a CZ |
120 | } |
121 | ||
7ba6bc91 CZ |
122 | public double getTargetShootingSpeed() { |
123 | return targetShootingSpeed; | |
f625e57a CZ |
124 | } |
125 | ||
126 | public void reverseIndexWheel() { | |
7ba6bc91 | 127 | this.setIndexWheelMotorVal(-DEFAULT_INDEXING_MOTOR_VALUE); |
f625e57a CZ |
128 | } |
129 | ||
130 | public void runIndexWheel() { | |
7ba6bc91 CZ |
131 | this.setIndexWheelMotorVal(DEFAULT_INDEXING_MOTOR_VALUE); |
132 | } | |
133 | ||
134 | public double calculateShooterSpeed() { | |
135 | this.wheelController.setSetPoint(targetShootingSpeed); | |
136 | double calculatedShooterIncrement = this.wheelController | |
137 | .calcPID(this.getShooterRPM()); | |
138 | currentShooterMotorValue += calculatedShooterIncrement; | |
139 | return currentShooterMotorValue; | |
140 | } | |
141 | ||
142 | public void initializePIDController() { | |
143 | this.wheelController = new PIDController(wheelP, wheelI, wheelD); | |
144 | this.wheelController.setDoneRange(10); | |
145 | this.wheelController.setMaxOutput(1.0); | |
146 | this.wheelController.setMinDoneCycles(3); | |
147 | this.wheelController.setSetPoint(this.targetShootingSpeed); | |
148 | this.currentShooterMotorValue = 0; | |
381dad77 | 149 | } |
185e0c8d RR |
150 | |
151 | public Value getPistonValue() { | |
152 | return piston.get(); | |
153 | } | |
154 | ||
155 | public void setHighGear() { | |
156 | changeGear(Constants.Shooter.HIGH_GEAR); | |
157 | } | |
158 | ||
159 | public void setLowGear() { | |
160 | changeGear(Constants.Shooter.LOW_GEAR); | |
161 | } | |
162 | ||
163 | private void changeGear(DoubleSolenoid.Value gear) { | |
164 | piston.set(gear); | |
165 | } | |
79ba119a | 166 | } |