Commit | Line | Data |
---|---|---|
aa160dfd ME |
1 | package org.usfirst.frc.team3501.robot.commands.driving; |
2 | ||
3 | import org.usfirst.frc.team3501.robot.Robot; | |
e12d6901 CZ |
4 | import org.usfirst.frc.team3501.robot.subsystems.DriveTrain; |
5 | import org.usfirst.frc.team3501.robot.utils.PIDController; | |
aa160dfd | 6 | |
e12d6901 | 7 | import edu.wpi.first.wpilibj.Preferences; |
aa160dfd | 8 | import edu.wpi.first.wpilibj.command.Command; |
b5ddf3e2 | 9 | import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; |
aa160dfd ME |
10 | |
11 | /** | |
c0e9f911 ME |
12 | * This command makes the robot drive a specified distance using encoders on the |
13 | * robot and using a feedback loop | |
aa160dfd | 14 | * |
e12d6901 CZ |
15 | * parameters: distance the robot will move in inches motorVal: the motor input |
16 | * to set the motors to | |
aa160dfd ME |
17 | */ |
18 | public class DriveDistance extends Command { | |
e12d6901 | 19 | private DriveTrain driveTrain = Robot.getDriveTrain(); |
c9cdc810 | 20 | private double maxTimeOut; |
e12d6901 | 21 | private double target; |
35527abe CZ |
22 | private double zeroAngle; |
23 | private Preferences prefs; | |
24 | private PIDController driveController; | |
e12d6901 | 25 | |
b5ddf3e2 | 26 | private double driveStraightGyroP; |
aa160dfd | 27 | |
db326f40 | 28 | public DriveDistance(double distance, double maxTimeOut) { |
9b35aa55 | 29 | requires(driveTrain); |
174f415c | 30 | this.target = distance; |
c9cdc810 | 31 | this.maxTimeOut = maxTimeOut; |
b5ddf3e2 ES |
32 | driveStraightGyroP = SmartDashboard.getNumber(driveTrain.DRIVE_GYRO_P_Val, |
33 | driveTrain.PID_ERROR); | |
d3ed4499 | 34 | |
9ffd117a E |
35 | this.driveController = driveTrain.getDriveController(); |
36 | this.driveController.setDoneRange(0.5); | |
c9cdc810 | 37 | this.driveController.setMaxOutput(1.0); |
e12d6901 | 38 | this.driveController.setMinDoneCycles(5); |
d17d868d | 39 | } |
40 | ||
d17d868d | 41 | @Override |
42 | protected void initialize() { | |
e12d6901 | 43 | this.driveTrain.resetEncoders(); |
e12d6901 | 44 | this.driveController.setSetPoint(this.target); |
d17d868d | 45 | } |
46 | ||
d17d868d | 47 | @Override |
48 | protected void execute() { | |
b5ddf3e2 | 49 | double xVal = driveStraightGyroP * (driveTrain.getAngle() - zeroAngle); |
35527abe | 50 | double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance()); |
e12d6901 | 51 | |
8e4c083c CZ |
52 | double leftDrive = yVal - xVal; |
53 | double rightDrive = yVal + xVal; | |
e12d6901 | 54 | this.driveTrain.setMotorValues(leftDrive, rightDrive); |
b5ddf3e2 ES |
55 | |
56 | System.out.println( | |
57 | "PID VALS: " + driveController.getP() + " " + driveController.getI() | |
58 | + " " + driveController.getD()); | |
59 | ||
60 | System.out.println(driveTrain.getAvgEncoderDistance()); | |
d17d868d | 61 | } |
62 | ||
d17d868d | 63 | @Override |
64 | protected boolean isFinished() { | |
35527abe CZ |
65 | return timeSinceInitialized() >= maxTimeOut |
66 | || this.driveController.isDone(); | |
d17d868d | 67 | } |
68 | ||
d17d868d | 69 | @Override |
70 | protected void end() { | |
71 | } | |
72 | ||
d17d868d | 73 | @Override |
74 | protected void interrupted() { | |
e12d6901 | 75 | end(); |
d17d868d | 76 | } |
aa160dfd | 77 | } |