implement shooter pid
authorCindy Zhang <cindyzyx9@gmail.com>
Mon, 20 Feb 2017 23:50:37 +0000 (15:50 -0800)
committerCindy Zhang <cindyzyx9@gmail.com>
Mon, 20 Feb 2017 23:50:37 +0000 (15:50 -0800)
src/org/usfirst/frc/team3501/robot/Robot.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/subsystems/Shooter.java

index c446a8687b22642a025abafecabfa9ecaf167717..e6ad60d6482c586bd9221e7aa1f42db1b6d17ed4 100644 (file)
@@ -6,8 +6,10 @@ import org.usfirst.frc.team3501.robot.subsystems.Shooter;
 
 import edu.wpi.cscore.UsbCamera;
 import edu.wpi.first.wpilibj.CameraServer;
+import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.IterativeRobot;
 import edu.wpi.first.wpilibj.command.Scheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 
 public class Robot extends IterativeRobot {
   private static DriveTrain driveTrain;
@@ -56,11 +58,19 @@ public class Robot extends IterativeRobot {
 
   @Override
   public void teleopInit() {
-
   }
 
   @Override
   public void teleopPeriodic() {
     Scheduler.getInstance().run();
+    updateSmartDashboard();
+  }
+
+  public void updateSmartDashboard() {
+    SmartDashboard.putNumber("angle", driveTrain.getAngle());
+    SmartDashboard.putNumber("voltage",
+        DriverStation.getInstance().getBatteryVoltage());
+    SmartDashboard.putNumber("rpm", shooter.getShooterRPM());
+    SmartDashboard.putNumber("motor value", shooter.getCurrentShootingSpeed());
   }
 }
index 442897aa9e15eb71f22544f8b2170bb32f2d5b35..c5101fc7d0dea5e23353b3a6c6b890ad35247450 100644 (file)
@@ -23,6 +23,7 @@ public class RunFlyWheel extends Command {
   private double wheelI;
   private double wheelD;
   private double target;
+  private double shooterSpeed = 0;
 
   public RunFlyWheel(double maxTimeOut) {
 
@@ -46,9 +47,9 @@ public class RunFlyWheel extends Command {
   // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-    double shooterSpeed = this.wheelController
+    double calculatedShooterIncrement = this.wheelController
         .calcPID(this.shooter.getShooterRPM());
-
+    shooterSpeed += calculatedShooterIncrement;
     this.shooter.setFlyWheelMotorVal(shooterSpeed);
   }
 
index 047fad40885a8e2f5caad590004cab64493dc5bb..fa5426e90a21580e42d14c76e7f2d98ef9ac72ed 100644 (file)
@@ -26,7 +26,7 @@ public class RunFlyWheelContinuous extends Command {
   private double wheelI;
   private double wheelD;
   private double target;
-  double shooterSpeed = 0;
+  private double shooterSpeed = 0;
 
   public RunFlyWheelContinuous() {
     this.wheelP = this.shooter.wheelP;
@@ -37,7 +37,7 @@ public class RunFlyWheelContinuous extends Command {
     this.wheelController.setDoneRange(10);
     this.wheelController.setMaxOutput(1.0);
     this.wheelController.setMinDoneCycles(3);
-    this.target = 2700;
+    this.target = shooter.getCurrentShootingSpeed();
   }
 
   @Override
@@ -50,11 +50,7 @@ public class RunFlyWheelContinuous extends Command {
     double calculatedShooterIncrement = this.wheelController
         .calcPID(this.shooter.getShooterRPM());
     shooterSpeed += calculatedShooterIncrement;
-    if (shooterSpeed > 1.0)
-      this.shooter.setFlyWheelMotorVal(1.0);
-    else
-      this.shooter.setFlyWheelMotorVal(shooterSpeed);
-    // this.shooter.setFlyWheelMotorVal(this.shooter.CURRENT_SHOOTING_SPEED);
+    this.shooter.setFlyWheelMotorVal(shooterSpeed);
   }
 
   @Override
index 7a11c2d74440abff3dea25a9c2e60adbaad0e4d4..391eeafce1e1a3806c2ee1e5ad3aa1a910101688 100644 (file)
@@ -9,16 +9,16 @@ import com.ctre.CANTalon;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
-  public double wheelP = 0.0003, wheelI = 0, wheelD = -0.00004;
+  public double wheelP = 0.0001, wheelI = 0, wheelD = 0.0004;
   private static Shooter shooter;
   private static HallEffectSensor hallEffect;
   private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  public static final double DEFAULT_INDEXING_SPEED = -1.0;
-  public static final double DEFAULT_SHOOTING_SPEED = 0.75;
-  public static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED;
+  public static final double DEFAULT_INDEXING_SPEED = -0.75;
+  public static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm
+  private static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED;
 
-  public static final double SHOOTING_SPEED_INCREMENT = 0.05;
+  public static final double SHOOTING_SPEED_INCREMENT = 25;
 
   private Shooter() {
     flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);