Merge branch 'cindy/secondHood'
[3501/stronghold-2016] / 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.sensors.Lidar;
5
6 import edu.wpi.first.wpilibj.CANTalon;
7 import edu.wpi.first.wpilibj.CounterBase.EncodingType;
8 import edu.wpi.first.wpilibj.DoubleSolenoid;
9 import edu.wpi.first.wpilibj.Encoder;
10 import edu.wpi.first.wpilibj.command.Subsystem;
11
12 /***
13 * The Shooter consists of a platform and wheel, each controlled by separate
14 * motors. The piston controlling the platform pushes the ball onto the wheel.
15 * The wheel is controlled by a motor, which is running before the ball is
16 * pushed onto the wheel. The spinning wheel propels the ball.
17 *
18 * @author superuser
19 *
20 */
21
22 public class Shooter extends Subsystem {
23 private CANTalon shooter;
24 private DoubleSolenoid hood1, hood2, punch;
25 private Encoder encoder;
26 private Lidar lidar;
27
28 public Shooter() {
29 shooter = new CANTalon(Constants.Shooter.PORT);
30 hood1 = new DoubleSolenoid(Constants.Shooter.HOOD_FORWARD,
31 Constants.Shooter.HOOD_REVERSE);
32 hood2 = new DoubleSolenoid(Constants.Shooter.HOOD_FORWARD,
33 Constants.Shooter.HOOD_REVERSE);
34 punch = new DoubleSolenoid(Constants.Shooter.PUNCH_FORWARD,
35 Constants.Shooter.PUNCH_REVERSE);
36
37 encoder = new Encoder(Constants.Shooter.ENCODER_PORT_A,
38 Constants.Shooter.ENCODER_PORT_B, false, EncodingType.k4X);
39 }
40
41 /***
42 * This method checks to see if the ball has successfully passed through the
43 * intake rollers and is inside.
44 *
45 * @return whether the presence of the ball is true or false and returns the
46 * state of the condition (true or false).
47 */
48
49 public boolean isBallInside() {
50 return true;
51 }
52
53 public void setSpeed(double speed) {
54 if (speed > 1.0)
55 shooter.set(1.0);
56 else if (speed < -1.0)
57 shooter.set(-1.0);
58 else
59 shooter.set(speed);
60 }
61
62 public void stop() {
63 this.setSpeed(0.0);
64 }
65
66 public double getSpeed() {
67 return encoder.getRate();
68 }
69
70 /*
71 * We are going to map a lidar distance to a shooter speed that will be set to
72 * the shooter. This function does not yet exist so we will just use y=x but
73 * when testing commences we shall create the function
74 */
75 public double getShooterSpeed() {
76 double distanceToGoal = lidar.getDistance();
77 double shooterSpeed = distanceToGoal; // Function to be determined
78 return shooterSpeed;
79 }
80
81 // Use negative # for decrement. Positive for increment.
82
83 public void changeSpeed(double change) {
84 double newSpeed = getSpeed() + change;
85 setSpeed(newSpeed);
86 }
87
88 // Punch Commands
89 public void extendPunch() {
90 punch.set(Constants.Shooter.punch);
91 }
92
93 public void retractPunch() {
94 punch.set(Constants.Shooter.retract);
95 }
96
97 public void raiseHood() {
98 hood1.set(Constants.Shooter.open);
99 hood2.set(Constants.Shooter.open);
100 }
101
102 public void lowerHood() {
103 hood1.set(Constants.Shooter.closed);
104 hood2.set(Constants.Shooter.closed);
105 }
106
107 public boolean isHoodDown() {
108 if (hood1.get() == Constants.Shooter.open
109 && hood2.get() == Constants.Shooter.open)
110 return true;
111 return false;
112 }
113
114 @Override
115 protected void initDefaultCommand() {
116 }
117 }