Add the piston solenoid object to shooter and add punch methods/constants
[3501/stronghold-2016] / src / org / usfirst / frc / team3501 / robot / subsystems / Shooter.java
index 68c1d51ab1bb3550ac4b49b9547839ecf0e99c82..bda816f402fa2bae9c0ec35d09601275a9cbc7a9 100755 (executable)
@@ -1,17 +1,19 @@
 package org.usfirst.frc.team3501.robot.subsystems;
 
 import org.usfirst.frc.team3501.robot.Constants;
-import org.usfirst.frc.team3501.robot.Constants.Shooter.State;
 
 import edu.wpi.first.wpilibj.CANTalon;
+import edu.wpi.first.wpilibj.DoubleSolenoid;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
-  // TODO: check all files for control m characters
   private CANTalon shooter;
+  private DoubleSolenoid punch;
 
   public Shooter() {
     shooter = new CANTalon(Constants.Shooter.PORT);
+    punch = new DoubleSolenoid(Constants.Shooter.FORWARD_PORT,
+        Constants.Shooter.REVERSE_PORT);
   }
 
   public double getCurrentSetPoint() {
@@ -31,10 +33,6 @@ public class Shooter extends Subsystem {
     this.setSpeed(0.0);
   }
 
-  public State getState() {
-    return (this.getCurrentSetPoint() == 0) ? State.RUNNING : State.STOPPED;
-  }
-
   // Use negative # for decrement. Positive for increment.
   public void changeSpeed(double change) {
     double newSpeed = getCurrentSetPoint() + change;
@@ -47,6 +45,15 @@ public class Shooter extends Subsystem {
     }
   }
 
+  // Punch Commands
+  public void punch() {
+    punch.set(Constants.Shooter.punch);
+  }
+
+  public void resetPunch() {
+    punch.set(Constants.Shooter.retract);
+  }
+
   @Override
   protected void initDefaultCommand() {
   }