91da0989fd53f2cabead98f63f70ed67dadc6114
[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.command.Subsystem;
10
11 public class Shooter extends Subsystem {
12 public double wheelP = 0.0001, wheelI = 0, wheelD = 0.0004;
13 private static Shooter shooter;
14 private static HallEffectSensor hallEffect;
15 private final CANTalon flyWheel1, flyWheel2, indexWheel;
16
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;
20
21 private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
22
23 private Shooter() {
24 flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
25 flyWheel2 = new CANTalon(Constants.Shooter.FLY_WHEEL2);
26 indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL);
27
28 hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
29 }
30
31 /**
32 * Returns shooter object
33 *
34 * @return Shooter object
35 */
36 public static Shooter getShooter() {
37 if (shooter == null) {
38 shooter = new Shooter();
39 }
40 return shooter;
41 }
42
43 /**
44 * Sets fly wheel motor value to input.
45 *
46 * @param val
47 * motor value from -1 to 1(fastest forward)
48 */
49 public void setFlyWheelMotorVal(double val) {
50 val = MathLib.restrictToRange(val, 0.0, 1.0);
51 flyWheel1.set(val);
52 flyWheel2.set(val);
53 }
54
55 /**
56 * Stops fly wheel motor.
57 */
58 public void stopFlyWheel() {
59 flyWheel1.set(0);
60 flyWheel2.set(0);
61 }
62
63 /**
64 * Sets index wheel motor value to input.
65 *
66 * @param val
67 * motor value from -1 to 1(fastest forward)
68 */
69 public void setIndexWheelMotorVal(double val) {
70 val = MathLib.restrictToRange(val, -1.0, 1.0);
71 indexWheel.set(val);
72 }
73
74 /**
75 * Stops index wheel motor.
76 */
77 public void stopIndexWheel() {
78 indexWheel.set(0);
79 }
80
81 @Override
82 protected void initDefaultCommand() {
83
84 }
85
86 public double getShooterRPM() {
87 return hallEffect.getRPM();
88 }
89
90 public void setCurrentShootingSpeed(double Value) {
91 currentShootingSpeed = Value;
92 }
93
94 public void decrementCurrentShootingSpeed() {
95 this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
96 }
97
98 public void incrementCurrentShootingSpeed() {
99 this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
100 }
101
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);
116 }
117 }