From c726d04ade36dead56cd4b2f1b91a341ce90bdb6 Mon Sep 17 00:00:00 2001 From: AyushNigade Date: Sat, 11 Feb 2017 14:37:06 -0800 Subject: [PATCH] tweak auton middle gear command group --- .../frc/team3501/robot/commandgroups/AutonMiddleGear.java | 6 ++++-- .../frc/team3501/robot/commands/driving/DriveDistance.java | 4 ++-- .../frc/team3501/robot/commands/driving/TurnForAngle.java | 2 +- .../usfirst/frc/team3501/robot/subsystems/DriveTrain.java | 2 +- 4 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/org/usfirst/frc/team3501/robot/commandgroups/AutonMiddleGear.java b/src/org/usfirst/frc/team3501/robot/commandgroups/AutonMiddleGear.java index bd718b3..913bbd7 100644 --- a/src/org/usfirst/frc/team3501/robot/commandgroups/AutonMiddleGear.java +++ b/src/org/usfirst/frc/team3501/robot/commandgroups/AutonMiddleGear.java @@ -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)); diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java b/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java index bdd5a69..582cd80 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java @@ -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 diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java index 867f5ed..717f151 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -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 diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index 1ffb14d..3f76a86 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -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; -- 2.30.2