1 package org
.usfirst
.frc
.team3501
.robot
.commands
.driving
;
3 import org
.usfirst
.frc
.team3501
.robot
.Robot
;
4 import org
.usfirst
.frc
.team3501
.robot
.subsystems
.DriveTrain
;
5 import org
.usfirst
.frc
.team3501
.robot
.utils
.PIDController
;
7 import edu
.wpi
.first
.wpilibj
.Preferences
;
8 import edu
.wpi
.first
.wpilibj
.command
.Command
;
11 * This command makes the robot drive a specified distance using encoders on the
12 * robot and using a feedback loop
14 * parameters: distance the robot will move in inches motorVal: the motor input
15 * to set the motors to
17 public class DriveDistance
extends Command
{
18 private DriveTrain driveTrain
= Robot
.getDriveTrain();
19 private double maxTimeOut
;
20 private PIDController driveController
;
21 private PIDController gyroController
;
22 private Preferences prefs
;
24 private double target
;
29 private double driveP
;
30 private double driveI
;
31 private double driveD
;
33 public DriveDistance(double distance
, double motorVal
) {
35 this.maxTimeOut
= maxTimeOut
;
36 this.target
= distance
;
38 this.driveP
= driveTrain
.driveP
;
39 this.driveI
= driveTrain
.driveI
;
40 this.driveD
= driveTrain
.driveD
;
41 this.gyroP
= driveTrain
.defaultGyroP
;
42 this.gyroI
= driveTrain
.defaultGyroI
;
43 this.gyroD
= driveTrain
.defaultGyroD
;
44 this.driveController
= new PIDController(this.driveP
, this.driveI
,
46 this.driveController
.setDoneRange(0.5);
47 this.driveController
.setMaxOutput(1.0);
48 this.driveController
.setMinDoneCycles(5);
50 this.gyroController
= new PIDController(this.gyroP
, this.gyroI
, this.gyroD
);
51 this.gyroController
.setDoneRange(1);
52 this.gyroController
.setMinDoneCycles(5);
56 protected void initialize() {
57 this.driveTrain
.resetEncoders();
58 this.driveTrain
.resetGyro();
59 this.driveController
.setSetPoint(this.target
);
60 this.gyroController
.setSetPoint(this.driveTrain
.getZeroAngle());
64 protected void execute() {
66 double yVal
= this.driveController
67 .calcPID(this.driveTrain
.getAvgEncoderDistance());
69 if (this.driveTrain
.getAngle() - this.driveTrain
.getZeroAngle() < 30) {
70 xVal
= -this.gyroController
71 .calcPID(this.driveTrain
.getAngle() - this.driveTrain
.getZeroAngle());
73 double leftDrive
= yVal
- xVal
;
74 double rightDrive
= yVal
+ xVal
;
76 this.driveTrain
.setMotorValues(leftDrive
, rightDrive
);
78 driveTrain
.printEncoderOutput();
79 // System.out.println("turn: " + xVal);
83 protected boolean isFinished() {
84 boolean isDone
= this.driveController
.isDone();
85 if (timeSinceInitialized() >= maxTimeOut
|| isDone
)
86 System
.out
.println("time: " + timeSinceInitialized());
87 return timeSinceInitialized() >= maxTimeOut
|| isDone
;
91 protected void end() {
96 protected void interrupted() {