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 ME |
8 | import edu.wpi.first.wpilibj.command.Command; |
9 | ||
10 | /** | |
c0e9f911 ME |
11 | * This command makes the robot drive a specified distance using encoders on the |
12 | * robot and using a feedback loop | |
aa160dfd | 13 | * |
e12d6901 CZ |
14 | * parameters: distance the robot will move in inches motorVal: the motor input |
15 | * to set the motors to | |
aa160dfd ME |
16 | */ |
17 | public class DriveDistance extends Command { | |
e12d6901 CZ |
18 | private DriveTrain driveTrain = Robot.getDriveTrain(); |
19 | private double maxTimeOut; | |
e12d6901 | 20 | private double target; |
35527abe CZ |
21 | private double zeroAngle; |
22 | private Preferences prefs; | |
23 | private PIDController driveController; | |
e12d6901 | 24 | |
35527abe | 25 | private double gyroP; |
aa160dfd | 26 | |
db326f40 | 27 | public DriveDistance(double distance, double maxTimeOut) { |
9b35aa55 | 28 | requires(driveTrain); |
174f415c CZ |
29 | this.maxTimeOut = maxTimeOut; |
30 | this.target = distance; | |
31 | ||
225f2b59 E |
32 | this.gyroP = driveTrain.getGyroController().getP(); |
33 | ||
9ffd117a E |
34 | this.driveController = driveTrain.getDriveController(); |
35 | this.driveController.setDoneRange(0.5); | |
e12d6901 CZ |
36 | this.driveController.setMaxOutput(1.0); |
37 | this.driveController.setMinDoneCycles(5); | |
d17d868d | 38 | } |
39 | ||
d17d868d | 40 | @Override |
41 | protected void initialize() { | |
e12d6901 | 42 | this.driveTrain.resetEncoders(); |
e12d6901 | 43 | this.driveController.setSetPoint(this.target); |
a756c730 | 44 | // test |
d17d868d | 45 | } |
46 | ||
d17d868d | 47 | @Override |
48 | protected void execute() { | |
35527abe CZ |
49 | double xVal = gyroP * (driveTrain.getAngle() - zeroAngle); |
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); |
d17d868d | 55 | } |
56 | ||
d17d868d | 57 | @Override |
58 | protected boolean isFinished() { | |
35527abe CZ |
59 | return timeSinceInitialized() >= maxTimeOut |
60 | || this.driveController.isDone(); | |
d17d868d | 61 | } |
62 | ||
d17d868d | 63 | @Override |
64 | protected void end() { | |
65 | } | |
66 | ||
d17d868d | 67 | @Override |
68 | protected void interrupted() { | |
e12d6901 | 69 | end(); |
d17d868d | 70 | } |
aa160dfd | 71 | } |