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