Merged with master
authorRohan Rodrigues <rohanrodrigues19@gmail.com>
Thu, 9 Mar 2017 00:49:44 +0000 (16:49 -0800)
committerRohan Rodrigues <rohanrodrigues19@gmail.com>
Thu, 9 Mar 2017 00:49:44 +0000 (16:49 -0800)
19 files changed:
src/org/usfirst/frc/team3501/robot/Constants.java
src/org/usfirst/frc/team3501/robot/OI.java
src/org/usfirst/frc/team3501/robot/Robot.java
src/org/usfirst/frc/team3501/robot/commandgroups/AutonHopperShoot.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/commandgroups/AutonShoot.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/commandgroups/Shoot.java
src/org/usfirst/frc/team3501/robot/commands/climber/ToggleWinch.java
src/org/usfirst/frc/team3501/robot/commands/driving/BrakeCANTalons.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/commands/driving/CoastCANTalons.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java
src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java
src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java
src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java

index 91a5cc7f2a664980af0a0a51f5bb4aa1aac627e8..312e0c355a8b584dcda01b230f30bb15d121471a 100644 (file)
@@ -16,7 +16,6 @@ public class Constants {
     public final static int RIGHT_STICK_PORT = 1;
 
     // Need to fill in the port numbers of the following buttons
-    public final static int TOGGLE_WINCH_PORT = 0;
     public final static int TOGGLE_FLYWHEEL_PORT = 4;
     public final static int RUN_INDEXWHEEL_PORT = 1;
     public final static int REVERSE_INDEXWHEEL_PORT = 2;
@@ -25,7 +24,12 @@ public class Constants {
     public final static int REVERSE_INTAKE_PORT = 4;
     public static final int INCREASE_SHOOTER_SPEED_PORT = 6;
     public static final int DECREASE_SHOOTER_SPEED_PORT = 2;
+
     public static final int CHANGE_CAMERA_VIEW = 6;
+
+    public static final int BRAKE_CANTALONS_PORT = 5;
+    public static final int COAST_CANTALONS_PORT = 3;
+
   }
 
   public static class Shooter {
@@ -38,8 +42,9 @@ public class Constants {
 
     public final static int TOGGLE_INDEXER = 8;
 
-    public static final int PISTON_MODULE = 10, PISTON_FORWARD = 4,
+    public static final int MODULE_NUMBER = 10, PISTON_FORWARD = 4,
         PISTON_REVERSE = 5;
+
     public static final Value HIGH_GEAR = DoubleSolenoid.Value.kForward;
     public static final Value LOW_GEAR = DoubleSolenoid.Value.kReverse;
   }
@@ -47,8 +52,8 @@ public class Constants {
   public static class DriveTrain {
     // GEARS
     public static final int PISTON_MODULE = 10, LEFT_GEAR_PISTON_FORWARD = 0,
-        LEFT_GEAR_PISTON_REVERSE = 1, RIGHT_GEAR_PISTON_FORWARD = 2,
-        RIGHT_GEAR_PISTON_REVERSE = 3;
+        LEFT_GEAR_PISTON_REVERSE = 1, RIGHT_GEAR_PISTON_FORWARD = 3,
+        RIGHT_GEAR_PISTON_REVERSE = 2;
     public static final Value HIGH_GEAR = DoubleSolenoid.Value.kForward;
     public static final Value LOW_GEAR = DoubleSolenoid.Value.kReverse;
 
index 07ad53c765b9f50318f9cb024d4a46c1344e02e1..880894f810c81705e164e0e1edeb922b0b4cb493 100644 (file)
@@ -1,6 +1,5 @@
 package org.usfirst.frc.team3501.robot;
 
-import org.usfirst.frc.team3501.robot.commands.climber.ToggleWinch;
 import org.usfirst.frc.team3501.robot.commands.driving.ToggleGear;
 import org.usfirst.frc.team3501.robot.commands.intake.ReverseIntakeContinuous;
 import org.usfirst.frc.team3501.robot.commands.intake.RunIntakeContinuous;
@@ -20,7 +19,6 @@ public class OI /* implements KeyListener */ {
   private static OI oi;
   public static Joystick leftJoystick;
   public static Joystick rightJoystick;
-  public static Button toggleWinch;
 
   public static Button runIndexWheel;
   public static Button reverseIndexWheel;
@@ -39,6 +37,9 @@ public class OI /* implements KeyListener */ {
   private static Button togglePiston;
   private static Button toggleDriveTrainPiston;
 
+  public static Button brakeCANTalons;
+  public static Button coastCANTalons;
+
   public OI() {
 
     leftJoystick = new Joystick(Constants.OI.LEFT_STICK_PORT);
@@ -67,10 +68,6 @@ public class OI /* implements KeyListener */ {
         Constants.OI.REVERSE_INTAKE_PORT);
     reverseIntake.whileHeld(new ReverseIntakeContinuous());
 
-    toggleWinch = new JoystickButton(leftJoystick,
-        Constants.OI.TOGGLE_WINCH_PORT);
-    toggleWinch.whenPressed(new ToggleWinch());
-
     increaseShooterSpeed = new JoystickButton(leftJoystick,
         Constants.OI.INCREASE_SHOOTER_SPEED_PORT);
     increaseShooterSpeed.whenPressed(new IncreaseShootingSpeed());
@@ -90,6 +87,14 @@ public class OI /* implements KeyListener */ {
     toggleDriveTrainPiston = new JoystickButton(rightJoystick,
         Constants.DriveTrain.TOGGLE_DRIVE_PISTON);
     toggleDriveTrainPiston.whenPressed(new ToggleGear());
+
+    brakeCANTalons = new JoystickButton(rightJoystick,
+        Constants.OI.BRAKE_CANTALONS_PORT);
+    brakeCANTalons.whenPressed(new BrakeCANTalons());
+
+    coastCANTalons = new JoystickButton(rightJoystick,
+        Constants.OI.COAST_CANTALONS_PORT);
+    coastCANTalons.whenPressed(new CoastCANTalons());
   }
 
   public static OI getOI() {
index e72f07e03b85c3a2c8512acf2989800469be42af..5e9bd3cbdb496727cd9722efc1630c5ad13c2228 100644 (file)
@@ -24,9 +24,12 @@ public class Robot extends IterativeRobot {
     oi = OI.getOI();
     shooter = Shooter.getShooter();
     intake = Intake.getIntake();
+
     server = CameraServer.getInstance();
     UsbCamera climberCam = server.startAutomaticCapture("climbercam", 0);
     UsbCamera intakeCam = server.startAutomaticCapture("intakecam", 1);
+
+    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
   }
 
   public static DriveTrain getDriveTrain() {
@@ -56,6 +59,7 @@ public class Robot extends IterativeRobot {
   @Override
   public void autonomousInit() {
     driveTrain.setHighGear();
+    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
   }
 
   @Override
@@ -65,19 +69,36 @@ public class Robot extends IterativeRobot {
 
   @Override
   public void teleopInit() {
+    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
   }
 
   @Override
   public void teleopPeriodic() {
+    // driveTrain.printEncoderOutput();
     Scheduler.getInstance().run();
     updateSmartDashboard();
   }
 
+  @Override
+  public void disabledInit() {
+    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_BRAKE_MODE);
+  }
+  //
+  // @Override
+  // public void disabledPeriodic() {
+  // Scheduler.getInstance().add(new RunFlyWheel(2));
+  // }
+
   public void updateSmartDashboard() {
+    SmartDashboard.putNumber("left encode ",
+        driveTrain.getLeftEncoderDistance());
+    SmartDashboard.putNumber("right encoder",
+        driveTrain.getRightEncoderDistance());
     SmartDashboard.putNumber("angle", driveTrain.getAngle());
     SmartDashboard.putNumber("voltage",
         DriverStation.getInstance().getBatteryVoltage());
     SmartDashboard.putNumber("rpm", shooter.getShooterRPM());
-    SmartDashboard.putNumber("motor value", shooter.getCurrentShootingSpeed());
+    SmartDashboard.putNumber("target shooting",
+        shooter.getTargetShootingSpeed());
   }
 }
diff --git a/src/org/usfirst/frc/team3501/robot/commandgroups/AutonHopperShoot.java b/src/org/usfirst/frc/team3501/robot/commandgroups/AutonHopperShoot.java
new file mode 100644 (file)
index 0000000..eb412d2
--- /dev/null
@@ -0,0 +1,45 @@
+package org.usfirst.frc.team3501.robot.commandgroups;
+
+import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.Constants.Direction;
+import org.usfirst.frc.team3501.robot.commands.driving.DriveDistance;
+import org.usfirst.frc.team3501.robot.commands.driving.TurnForAngle;
+
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.command.CommandGroup;
+import edu.wpi.first.wpilibj.command.WaitCommand;
+
+/**
+ * // Robot starts in middle, goes to the hopper, then boiler,then shoots during
+ * auton
+ */
+public class AutonHopperShoot extends CommandGroup {
+  // If red, direction is right; if blue, direction is left
+  private static final Direction DIRECTION_TO_HOPPER = Constants.Direction.LEFT;
+  // If red, direction is left; if blue, direction is right
+  private static final Direction DIRECTION_TO_BOILER = Constants.Direction.RIGHT;
+
+  private Timer timer;
+
+  public AutonHopperShoot() {
+    timer = new Timer();
+    // Robot drives from center to front of airship
+    addSequential(new DriveDistance(78.5, 2.7));
+    // Robot turns towards hopper
+    addSequential(new TurnForAngle(90.0, DIRECTION_TO_HOPPER, 2.5));
+    // Robot drives into hopper switch
+    addSequential(new DriveDistance(42.12, 5.25));
+    addSequential(new WaitCommand(1));
+    // Robot backs up from switch
+    addSequential(new DriveDistance(-25.0, 2.9));
+    // Robot turns towards the boiler
+    addSequential(new TurnForAngle(90.0, DIRECTION_TO_HOPPER, 5.0));
+    // Robot drives to boiler
+    addSequential(new DriveDistance(90, 5.0));
+    // Robot turns parallel to boiler
+    addSequential(new TurnForAngle(45, DIRECTION_TO_BOILER, 5.0));
+    // Shoot
+    addSequential(new Shoot(15 - timeSinceInitialized()));
+  }
+
+}
diff --git a/src/org/usfirst/frc/team3501/robot/commandgroups/AutonShoot.java b/src/org/usfirst/frc/team3501/robot/commandgroups/AutonShoot.java
new file mode 100644 (file)
index 0000000..c2af771
--- /dev/null
@@ -0,0 +1,26 @@
+package org.usfirst.frc.team3501.robot.commandgroups;
+
+import org.usfirst.frc.team3501.robot.Constants.Direction;
+import org.usfirst.frc.team3501.robot.commands.driving.DriveDistance;
+import org.usfirst.frc.team3501.robot.commands.driving.TurnForAngle;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+/**
+ *
+ */
+public class AutonShoot extends CommandGroup {
+
+  private static final int ROBOT_WIDTH = 40; // inches
+  private static final int ROBOT_LENGTH = 36; // inches
+
+  public AutonShoot() {
+    addSequential(
+        new DriveDistance(37.12 + (ROBOT_WIDTH / 2) - (ROBOT_LENGTH / 2), 5));
+    addSequential(new TurnForAngle(135, Direction.LEFT, 10));
+    addSequential(new DriveDistance(
+        (37.12 + (ROBOT_WIDTH / 2)) * Math.sqrt(2) - 26.25 - (ROBOT_LENGTH / 2),
+        10));
+    addSequential(new Shoot(15 - timeSinceInitialized()));
+  }
+}
index 18e3568a4a824c0cb8308edf0541a330014d97f3..cd2fe3371ba471ac43b4998582e2242e493b9932 100644 (file)
@@ -1,28 +1,19 @@
 package org.usfirst.frc.team3501.robot.commandgroups;
 
+import org.usfirst.frc.team3501.robot.commands.shooter.RunFlyWheel;
+import org.usfirst.frc.team3501.robot.commands.shooter.RunIndexWheel;
+
 import edu.wpi.first.wpilibj.command.CommandGroup;
+import edu.wpi.first.wpilibj.command.WaitCommand;
 
 /**
  *
  */
 public class Shoot extends CommandGroup {
 
-    public Shoot() {
-        // Add Commands here:
-        // e.g. addSequential(new Command1());
-        //      addSequential(new Command2());
-        // these will run in order.
-
-        // To run multiple commands at the same time,
-        // use addParallel()
-        // e.g. addParallel(new Command1());
-        //      addSequential(new Command2());
-        // Command1 and Command2 will run in parallel.
-
-        // A command group will require all of the subsystems that each member
-        // would require.
-        // e.g. if Command1 requires chassis, and Command2 requires arm,
-        // a CommandGroup containing them would require both the chassis and the
-        // arm.
-    }
+  public Shoot(double time) {
+    addParallel(new RunFlyWheel(time));
+    addSequential(new WaitCommand(2));
+    addParallel(new RunIndexWheel(time - 2));
+  }
 }
index 66c8364b1a37e78bcf993b5d4414e29d172322a7..3e60406cc66e332167c465d59dae56d08311b13f 100644 (file)
@@ -34,7 +34,7 @@ public class ToggleWinch extends Command {
 
   @Override
   protected boolean isFinished() {
-    return Robot.getOI().toggleWinch.get();
+    return false;
   }
 
   @Override
diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/BrakeCANTalons.java b/src/org/usfirst/frc/team3501/robot/commands/driving/BrakeCANTalons.java
new file mode 100644 (file)
index 0000000..0a19e57
--- /dev/null
@@ -0,0 +1,39 @@
+package org.usfirst.frc.team3501.robot.commands.driving;
+
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+/**
+ *
+ */
+public class BrakeCANTalons extends Command {
+  private DriveTrain driveTrain = Robot.getDriveTrain();
+
+  public BrakeCANTalons() {
+    requires(driveTrain);
+  }
+
+  @Override
+  protected void initialize() {
+    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_BRAKE_MODE);
+  }
+
+  @Override
+  protected void execute() {
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return true;
+  }
+
+  @Override
+  protected void end() {
+  }
+
+  @Override
+  protected void interrupted() {
+  }
+}
diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/CoastCANTalons.java b/src/org/usfirst/frc/team3501/robot/commands/driving/CoastCANTalons.java
new file mode 100644 (file)
index 0000000..ea676f2
--- /dev/null
@@ -0,0 +1,39 @@
+package org.usfirst.frc.team3501.robot.commands.driving;
+
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+/**
+ *
+ */
+public class CoastCANTalons extends Command {
+  private DriveTrain driveTrain = Robot.getDriveTrain();
+
+  public CoastCANTalons() {
+    requires(driveTrain);
+  }
+
+  @Override
+  protected void initialize() {
+    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
+  }
+
+  @Override
+  protected void execute() {
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return true;
+  }
+
+  @Override
+  protected void end() {
+  }
+
+  @Override
+  protected void interrupted() {
+  }
+}
index 717f15151d5b8512218b2e865acade3403cd9ced..b95c8223a69fccad10d0f3d3cc2bc882129bb6ed 100755 (executable)
@@ -36,9 +36,15 @@ public class TurnForAngle extends Command {
     this.maxTimeOut = maxTimeOut;
     this.target = Math.abs(angle);
 
-    this.gyroP = driveTrain.turnP;
-    this.gyroI = driveTrain.turnI;
-    this.gyroD = driveTrain.turnD;
+    if (angle > 90) {
+      this.gyroP = driveTrain.largeTurnP;
+      this.gyroI = driveTrain.largeTurnI;
+      this.gyroD = driveTrain.largeTurnD;
+    } else {
+      this.gyroP = driveTrain.smallTurnP;
+      this.gyroI = driveTrain.smallTurnI;
+      this.gyroD = driveTrain.smallTurnD;
+    }
 
     this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
     this.gyroController.setDoneRange(1);
index d105b60fea1707225e167e9fe129b5dc2b7ab887..7fa6cd0422aa3ab3fdaff86b2bcbff450050d9f7 100644 (file)
@@ -21,7 +21,7 @@ public class DecreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.decrementCurrentShootingSpeed();
+    shooter.decrementTargetShootingSpeed();
   }
 
   @Override
index 158848236a71a32a36447197bb55aa0cd34e1e03..8a2fbd99b4f868fc0c0e8a39862cb20dfd58e57d 100644 (file)
@@ -21,7 +21,7 @@ public class IncreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.incrementCurrentShootingSpeed();
+    shooter.incrementTargetShootingSpeed();
   }
 
   @Override
index 1bcf8970b21aa80fe0984fefcf247dbab5200822..8eb98bb90f26974f900ddbcb83486ad99859373b 100644 (file)
@@ -20,7 +20,7 @@ public class ResetShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.resetCurrentShootingSpeed();
+    shooter.resetTargetShootingSpeed();
   }
 
   @Override
index c5101fc7d0dea5e23353b3a6c6b890ad35247450..5abd73afe9fc64c798762a7dca6a92fd2a5b7b64 100644 (file)
@@ -1,4 +1,3 @@
-
 package org.usfirst.frc.team3501.robot.commands.shooter;
 
 import org.usfirst.frc.team3501.robot.Robot;
@@ -8,66 +7,49 @@ import org.usfirst.frc.team3501.robot.utils.PIDController;
 import edu.wpi.first.wpilibj.command.Command;
 
 /**
- * This command runs the fly wheel at a specific speed using a PID Controller
- * for accuracy for a given time. The fly wheel is intended to shoot balls fed
- * by the intake wheel.
+ * This command runs the fly wheel continuously at a set speed using a PID
+ * Controller when OI button managing fly wheel is pressed. The command will run
+ * the fly wheel motor until the button triggering it is released.
+ *
+ * Should only be run from the operator interface.
+ *
+ * pre-condition: This command must be run by a button in OI, with
+ * button.whileHeld(...).
  *
  * @author Shaina & Chris
  */
 public class RunFlyWheel extends Command {
   private Shooter shooter = Robot.getShooter();
-  private double maxTimeOut;
+  double time;
 
   private PIDController wheelController;
-  private double wheelP;
-  private double wheelI;
-  private double wheelD;
-  private double target;
-  private double shooterSpeed = 0;
-
-  public RunFlyWheel(double maxTimeOut) {
 
-    this.wheelP = this.shooter.wheelP;
-    this.wheelI = this.shooter.wheelI;
-    this.wheelD = this.shooter.wheelD;
-    this.wheelController = new PIDController(this.wheelP, this.wheelI,
-        this.wheelD);
-    this.wheelController.setDoneRange(0.5);
-    this.wheelController.setMaxOutput(1.0);
-    this.wheelController.setMinDoneCycles(3);
-    this.target = this.shooter.getCurrentShootingSpeed();
+  public RunFlyWheel(double time) {
+    this.time = time;
   }
 
-  // Called just before this Command runs the first time
   @Override
   protected void initialize() {
-    this.wheelController.setSetPoint(this.target);
+    shooter.initializePIDController();
   }
 
-  // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-    double calculatedShooterIncrement = this.wheelController
-        .calcPID(this.shooter.getShooterRPM());
-    shooterSpeed += calculatedShooterIncrement;
-    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+    shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
   }
 
-  // Make this return true when this Command no longer needs to run execute()
   @Override
   protected boolean isFinished() {
-    return timeSinceInitialized() >= maxTimeOut;
+    return timeSinceInitialized() >= time;
   }
 
-  // Called once after isFinished returns true
   @Override
   protected void end() {
     this.shooter.stopFlyWheel();
   }
 
-  // Called when another command which requires one or more of the same
-  // subsystems is scheduled to run
   @Override
   protected void interrupted() {
+    end();
   }
 }
index fa5426e90a21580e42d14c76e7f2d98ef9ac72ed..86c31f7eecd523ebc2a274a6b4d1d58bb74d45ed 100644 (file)
@@ -22,35 +22,18 @@ public class RunFlyWheelContinuous extends Command {
   private Shooter shooter = Robot.getShooter();
 
   private PIDController wheelController;
-  private double wheelP;
-  private double wheelI;
-  private double wheelD;
-  private double target;
-  private double shooterSpeed = 0;
 
   public RunFlyWheelContinuous() {
-    this.wheelP = this.shooter.wheelP;
-    this.wheelI = this.shooter.wheelI;
-    this.wheelD = this.shooter.wheelD;
-    this.wheelController = new PIDController(this.wheelP, this.wheelI,
-        this.wheelD);
-    this.wheelController.setDoneRange(10);
-    this.wheelController.setMaxOutput(1.0);
-    this.wheelController.setMinDoneCycles(3);
-    this.target = shooter.getCurrentShootingSpeed();
   }
 
   @Override
   protected void initialize() {
-    this.wheelController.setSetPoint(this.target);
+    shooter.initializePIDController();
   }
 
   @Override
   protected void execute() {
-    double calculatedShooterIncrement = this.wheelController
-        .calcPID(this.shooter.getShooterRPM());
-    shooterSpeed += calculatedShooterIncrement;
-    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+    shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
   }
 
   @Override
index d9966f1171494ace578ccc72ae081a5bbed46c10..6abb095b60a0a5ac74de61627244f479ae2248f6 100644 (file)
@@ -39,7 +39,9 @@ public class RunIndexWheel extends Command {
   @Override
   protected void execute() {
     double shooterSpeed = shooter.getShooterRPM();
-    if (shooterSpeed > 0)
+    double targetShooterSpeed = shooter.getTargetShootingSpeed();
+    double threshold = shooter.getRPMThreshold();
+    if (Math.abs(shooterSpeed - targetShooterSpeed) <= threshold)
       shooter.runIndexWheel();
   }
 
index 2004c1d506438e2979a3f334f1efa5da251bd908..ccc0e4374d6223121eefff87bc28ced1bee495c2 100644 (file)
@@ -24,24 +24,18 @@ public class RunIndexWheelContinuous extends Command {
 
   /**
    * See JavaDoc comment in class for details
-   *
-   * @param motorVal
-   *          value range from -1 to 1
    */
   public RunIndexWheelContinuous() {
     requires(shooter);
   }
 
-  // Called just before this Command runs the first time
   @Override
   protected void initialize() {
     t.start();
   }
 
-  // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-
     if (t.get() >= 1) {
       if (Shooter.getShooter().getPistonValue() == Constants.Shooter.LOW_GEAR) {
         Shooter.getShooter().setHighGear();
@@ -53,16 +47,14 @@ public class RunIndexWheelContinuous extends Command {
 
     if (shooter.isShooterRPMWithinRangeOfTargetSpeed(25))
       shooter.runIndexWheel();
+
   }
 
-  // Called once after isFinished returns true
   @Override
   protected void end() {
     shooter.stopIndexWheel();
   }
 
-  // Called when another command which requires one or more of the same
-  // subsystems is scheduled to run
   @Override
   protected void interrupted() {
     end();
@@ -71,7 +63,6 @@ public class RunIndexWheelContinuous extends Command {
   @Override
   protected boolean isFinished() {
     return false;
-
   }
 
 }
index 32ec7b221ab237ef17747dfa46f47f8246ace31b..bad303aebe622f0db77aa8a41d45e79b92c68325 100644 (file)
@@ -14,8 +14,10 @@ import edu.wpi.first.wpilibj.RobotDrive;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class DriveTrain extends Subsystem {
-  public static double driveP = 0.006, driveI = 0.0011, driveD = -0.002;
-  public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
+  public static double driveP = 0.012, driveI = 0.0011, driveD = -0.002;
+  public static double smallTurnP = 0.004, smallTurnI = 0.0013,
+      smallTurnD = 0.005;
+  public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006;
   public static double driveStraightGyroP = 0.01;
 
   public static final double WHEEL_DIAMETER = 4; // inches
@@ -27,6 +29,9 @@ public class DriveTrain extends Subsystem {
   public static final double TIME_TO_CLIMB_FOR = 0;
   public static final double CLIMBER_SPEED = 0;
 
+  public static final boolean DRIVE_BRAKE_MODE = true;
+  public static final boolean DRIVE_COAST_MODE = false;
+
   private static DriveTrain driveTrain;
 
   private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
@@ -77,8 +82,8 @@ public class DriveTrain extends Subsystem {
 
   // DRIVE METHODS
   public void setMotorValues(double left, double right) {
-    left = MathLib.restrictToRange(left, 0.0, 1.0);
-    right = MathLib.restrictToRange(right, 0.0, 1.0);
+    left = MathLib.restrictToRange(left, -1.0, 1.0);
+    right = MathLib.restrictToRange(right, -1.0, 1.0);
 
     frontLeft.set(left);
     rearLeft.set(left);
@@ -191,4 +196,12 @@ public class DriveTrain extends Subsystem {
   protected void initDefaultCommand() {
     setDefaultCommand(new JoystickDrive());
   }
+
+  public void setCANTalonsBrakeMode(boolean mode) {
+    frontLeft.enableBrakeMode(mode);
+    rearLeft.enableBrakeMode(mode);
+
+    frontRight.enableBrakeMode(mode);
+    rearRight.enableBrakeMode(mode);
+  }
 }
index 75737a6f0ce2ebf828a96c48647c158ec7729e10..820bc6a85c25f2429f5cf9c90153d48475914190 100644 (file)
@@ -3,6 +3,7 @@ package org.usfirst.frc.team3501.robot.subsystems;
 import org.usfirst.frc.team3501.robot.Constants;
 import org.usfirst.frc.team3501.robot.MathLib;
 import org.usfirst.frc.team3501.robot.utils.HallEffectSensor;
+import org.usfirst.frc.team3501.robot.utils.PIDController;
 
 import com.ctre.CANTalon;
 
@@ -11,17 +12,21 @@ import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
-  public double wheelP = 0.0001, wheelI = 0, wheelD = 0.0004;
+  public double wheelP = 0.00007, wheelI = 0, wheelD = 0.0008;
   private static Shooter shooter;
   private static HallEffectSensor hallEffect;
   private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  private static final double DEFAULT_INDEXING_SPEED = -0.75;
-  private static final double DEFAULT_SHOOTING_SPEED = 2800; // rpm
-  private static final double SHOOTING_SPEED_INCREMENT = 25;
+  private PIDController wheelController;
+
+  private static final double RPM_THRESHOLD = 10;
+  private static final double DEFAULT_INDEXING_MOTOR_VALUE = -0.75;
+  private static final double DEFAULT_SHOOTING_SPEED = 3100; // rpm
+  private static final double SHOOTING_SPEED_INCREMENT = 50;
   private static final int ACCEPTABLE_SHOOTING_DEVIATION = 300;
 
-  private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
+  private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
+  private double currentShooterMotorValue = 0;
 
   private final DoubleSolenoid piston;
 
@@ -32,7 +37,7 @@ public class Shooter extends Subsystem {
 
     hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
 
-    piston = new DoubleSolenoid(Constants.Shooter.PISTON_MODULE,
+    piston = new DoubleSolenoid(Constants.Shooter.MODULE_NUMBER,
         Constants.Shooter.PISTON_FORWARD, Constants.Shooter.PISTON_REVERSE);
   }
 
@@ -91,36 +96,57 @@ public class Shooter extends Subsystem {
 
   }
 
+  public double getRPMThreshold() {
+    return RPM_THRESHOLD;
+  }
+
   public double getShooterRPM() {
     return hallEffect.getRPM();
   }
 
-  public void setCurrentShootingSpeed(double Value) {
-    currentShootingSpeed = Value;
+  public void setTargetShootingSpeed(double Value) {
+    targetShootingSpeed = Value;
   }
 
-  public void decrementCurrentShootingSpeed() {
-    this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
+  public void decrementTargetShootingSpeed() {
+    this.targetShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
   }
 
-  public void incrementCurrentShootingSpeed() {
-    this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
+  public void incrementTargetShootingSpeed() {
+    this.targetShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
   }
 
-  public void resetCurrentShootingSpeed() {
-    this.currentShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
+  public void resetTargetShootingSpeed() {
+    this.targetShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
   }
 
-  public double getCurrentShootingSpeed() {
-    return currentShootingSpeed;
+  public double getTargetShootingSpeed() {
+    return targetShootingSpeed;
   }
 
   public void reverseIndexWheel() {
-    this.setIndexWheelMotorVal(-DEFAULT_INDEXING_SPEED);
+    this.setIndexWheelMotorVal(-DEFAULT_INDEXING_MOTOR_VALUE);
   }
 
   public void runIndexWheel() {
-    this.setIndexWheelMotorVal(DEFAULT_INDEXING_SPEED);
+    this.setIndexWheelMotorVal(DEFAULT_INDEXING_MOTOR_VALUE);
+  }
+
+  public double calculateShooterSpeed() {
+    this.wheelController.setSetPoint(targetShootingSpeed);
+    double calculatedShooterIncrement = this.wheelController
+        .calcPID(this.getShooterRPM());
+    currentShooterMotorValue += calculatedShooterIncrement;
+    return currentShooterMotorValue;
+  }
+
+  public void initializePIDController() {
+    this.wheelController = new PIDController(wheelP, wheelI, wheelD);
+    this.wheelController.setDoneRange(10);
+    this.wheelController.setMaxOutput(1.0);
+    this.wheelController.setMinDoneCycles(3);
+    this.wheelController.setSetPoint(this.targetShootingSpeed);
+    this.currentShooterMotorValue = 0;
   }
 
   public Value getPistonValue() {