delete angleAdjuster(cantalon), add hood(double solenoid) and methods for hood
[3501/stronghold-2016] / src / org / usfirst / frc / team3501 / robot / subsystems / Shooter.java
index 22239e49ee945c5bd0a9a163d9a9da7160233db2..f547ab0ee84fa2ae9399eb75898534218615ba07 100755 (executable)
@@ -1,10 +1,8 @@
 package org.usfirst.frc.team3501.robot.subsystems;
 
 import org.usfirst.frc.team3501.robot.Constants;
-import org.usfirst.frc.team3501.robot.Lidar;
-import org.usfirst.frc.team3501.robot.MathLib;
+import org.usfirst.frc.team3501.robot.sensors.Lidar;
 
-import edu.wpi.first.wpilibj.AnalogPotentiometer;
 import edu.wpi.first.wpilibj.CANTalon;
 import edu.wpi.first.wpilibj.CounterBase.EncodingType;
 import edu.wpi.first.wpilibj.DoubleSolenoid;
@@ -23,18 +21,16 @@ import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
   private CANTalon shooter;
-  private CANTalon angleAdjuster;
   private DoubleSolenoid hood, punch;
   private Encoder encoder;
   private Lidar lidar;
 
   public Shooter() {
-    leftLidar = new AnalogPotentiometer(0);
-    rightLidar = new AnalogPotentiometer(0);
     shooter = new CANTalon(Constants.Shooter.PORT);
-    angleAdjuster = new CANTalon(Constants.Shooter.ANGLE_ADJUSTER_PORT);
-    punch = new DoubleSolenoid(Constants.Shooter.PUNCH_FORWARD_PORT,
-        Constants.Shooter.PUNCH_REVERSE_PORT);
+    hood = new DoubleSolenoid(Constants.Shooter.HOOD_FORWARD,
+        Constants.Shooter.HOOD_REVERSE);
+    punch = new DoubleSolenoid(Constants.Shooter.PUNCH_FORWARD,
+        Constants.Shooter.PUNCH_REVERSE);
 
     encoder = new Encoder(Constants.Shooter.ENCODER_PORT_A,
         Constants.Shooter.ENCODER_PORT_B, false, EncodingType.k4X);
@@ -69,6 +65,17 @@ public class Shooter extends Subsystem {
     return encoder.getRate();
   }
 
+  /*
+   * We are going to map a lidar distance to a shooter speed that will be set to
+   * the shooter. This function does not yet exist so we will just use y=x but
+   * when testing commences we shall create the function
+   */
+  public double getShooterSpeed() {
+    double distanceToGoal = lidar.getDistance();
+    double shooterSpeed = distanceToGoal; // Function to be determined
+    return shooterSpeed;
+  }
+
   // Use negative # for decrement. Positive for increment.
 
   public void changeSpeed(double change) {
@@ -85,16 +92,15 @@ public class Shooter extends Subsystem {
     punch.set(Constants.Shooter.retract);
   }
 
-  @Override
-  protected void initDefaultCommand() {
+  public void raiseHood() {
+    hood.set(Constants.Shooter.open);
   }
 
-  public double getLeftDistanceToTower() {
-    // TODO: find the method that actually gets distance
-    return leftLidar.get();
+  public void lowerHood() {
+    hood.set(Constants.Shooter.closed);
   }
 
-  public double getRightDistanceToTower() {
-    return rightLidar.get();
+  @Override
+  protected void initDefaultCommand() {
   }
 }