public DriveDistance(double distance, double maxTimeOut) {
requires(driveTrain);
this.target = distance;
+
this.driveController = driveTrain.getDriveController();
this.driveController.setDoneRange(0.5);
- this.driveController.setMaxOutput(motorVal);
+ this.driveController.setMaxOutput(1.1);
this.driveController.setMinDoneCycles(5);
}
import edu.wpi.first.wpilibj.command.Subsystem;
public class DriveTrain extends Subsystem {
-
public static double driveP, driveI, driveD;
public static double turnP, turnI, turnD;
private PIDController gyroController;
private boolean isClimbing;
- private static double CLIMBER_SPEED;;
- public boolean shouldBeClimbing = false;
-
- private PIDController driveController;
- private PIDController gyroController;
private DriveTrain() {
// PID TUNING
driveController = new PIDController(driveP, driveI, driveD);
- gyroController = new PIDController(turnP, turnI, turnD
+ gyroController = new PIDController(turnP, turnI, turnD);
// MOTOR CONTROLLERS
frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);