tweak auton middle gear command group ayush/auton
authorAyushNigade <techiedude23@gmail.com>
Sat, 11 Feb 2017 22:37:06 +0000 (14:37 -0800)
committerAyushNigade <techiedude23@gmail.com>
Sat, 11 Feb 2017 22:37:06 +0000 (14:37 -0800)
src/org/usfirst/frc/team3501/robot/commandgroups/AutonMiddleGear.java
src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java
src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java

index bd718b341c6038983a6b9652ea7c64869e108eff..913bbd7e746c6b9b39d9dd4fc9be58a49b99564f 100644 (file)
@@ -6,6 +6,7 @@ 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;
+import edu.wpi.first.wpilibj.command.WaitCommand;
 
 /**
  *
@@ -18,8 +19,8 @@ import edu.wpi.first.wpilibj.command.CommandGroup;
  * again to cross the baseline.
  */
 public class AutonMiddleGear extends CommandGroup {
-  private static final double DISTANCE_TO_PEG = 91.3;
-  private static final double DISTANCE_TO_BACK_OUT = 29.75;
+  private static final double DISTANCE_TO_PEG = 91.3 - 32;
+  private static final double DISTANCE_TO_BACK_OUT = -29.75;
   private static final double THIRD_DISTANCE_TO_TRAVEL = 70;
   private static final double DISTANCE_TO_BASELINE = 50.5;
 
@@ -37,6 +38,7 @@ public class AutonMiddleGear extends CommandGroup {
    */
   public AutonMiddleGear(Direction direction) {
     addSequential(new DriveDistance(DISTANCE_TO_PEG, maxTimeOut));
+    addSequential(new WaitCommand(3));
     addSequential(new DriveDistance(DISTANCE_TO_BACK_OUT, maxTimeOut));
     addSequential(new TurnForAngle(ANGLE_TO_TURN, direction, maxTimeOut));
     addSequential(new DriveDistance(THIRD_DISTANCE_TO_TRAVEL, maxTimeOut));
index bdd5a69adb91f9df52936622a45ca2aacaf72c27..582cd80b69abb799a89a7b3afdcd56432d22a738 100755 (executable)
@@ -31,14 +31,13 @@ public class DriveDistance extends Command {
     requires(driveTrain);
     this.maxTimeOut = maxTimeOut;
     this.target = distance;
-    this.zeroAngle = driveTrain.getAngle();
 
     this.driveP = driveTrain.driveP;
     this.driveI = driveTrain.driveI;
     this.driveD = driveTrain.driveD;
     this.gyroP = driveTrain.driveStraightGyroP;
     this.driveController = new PIDController(driveP, driveI, driveD);
-    this.driveController.setDoneRange(0.5);
+    this.driveController.setDoneRange(1.0);
     this.driveController.setMaxOutput(1.0);
     this.driveController.setMinDoneCycles(5);
   }
@@ -47,6 +46,7 @@ public class DriveDistance extends Command {
   protected void initialize() {
     this.driveTrain.resetEncoders();
     this.driveController.setSetPoint(this.target);
+    this.zeroAngle = driveTrain.getAngle();
   }
 
   @Override
index 867f5eddf4d5865601fe068cec7739edde4c3732..717f15151d5b8512218b2e865acade3403cd9ced 100755 (executable)
@@ -35,7 +35,6 @@ public class TurnForAngle extends Command {
     this.direction = direction;
     this.maxTimeOut = maxTimeOut;
     this.target = Math.abs(angle);
-    this.zeroAngle = driveTrain.getAngle();
 
     this.gyroP = driveTrain.turnP;
     this.gyroI = driveTrain.turnI;
@@ -50,6 +49,7 @@ public class TurnForAngle extends Command {
   protected void initialize() {
     this.driveTrain.resetEncoders();
     this.gyroController.setSetPoint(this.target);
+    this.zeroAngle = driveTrain.getAngle();
   }
 
   @Override
index 1ffb14de3fba35fe495b2f2650ea173214184737..3f76a860f6907505d1431d64db159c0944de708d 100644 (file)
@@ -13,7 +13,7 @@ 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.001, driveD = -0.002;
+  public static double driveP = 0.012, driveI = 0.0011, driveD = -0.002;
   public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
   public static double driveStraightGyroP = 0.01;