public class DriveTrain extends Subsystem {
public static double driveP = 0.006, driveI = 0.001, driveD = -0.002;
- public static double defaultGyroP = 0.004, defaultGyroI = 0.0013,
- defaultGyroD = -0.005;
- private double gyroZero = 0;
+ public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
+ public static double driveStraightGyroP = 0.01;
public static final double WHEEL_DIAMETER = 6; // inches
public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
/ ENCODER_PULSES_PER_REVOLUTION;
-
+ public static final int MAINTAIN_CLIMBED_POSITION = 0;
+ public static final int TIME_TO_CLIMB_FOR = 0;
private static DriveTrain driveTrain;
+
private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
private final RobotDrive robotDrive;
private final Encoder leftEncoder, rightEncoder;
}
public void printEncoderOutput() {
- // System.out.println("left: " + getLeftEncoderDistance());
- // System.out.println("right: " + getRightEncoderDistance());
- System.out.println(getAvgEncoderDistance());
System.out.println("left: " + getLeftEncoderDistance());
System.out.println("right: " + getRightEncoderDistance());
+ // System.out.println(getAvgEncoderDistance());
}
public double getAvgEncoderDistance() {
// ------Gyro------//
public double getAngle() {
- return this.imu.getAngle() - this.gyroZero;
+ return this.imu.getAngle();
}
public void resetGyro() {
this.imu.reset();
}
- public double getZeroAngle() {
- return this.gyroZero;
- }
-
/*
* @return a value that is the current setpoint for the piston kReverse or
* KForward