| 1 | package org.usfirst.frc.team3501.robot.subsystems; |
| 2 | |
| 3 | import org.usfirst.frc.team3501.robot.Constants; |
| 4 | import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; |
| 5 | |
| 6 | import com.ctre.CANTalon; |
| 7 | |
| 8 | import edu.wpi.first.wpilibj.ADXRS450_Gyro; |
| 9 | import edu.wpi.first.wpilibj.Encoder; |
| 10 | import edu.wpi.first.wpilibj.RobotDrive; |
| 11 | import edu.wpi.first.wpilibj.command.Subsystem; |
| 12 | |
| 13 | public class DriveTrain extends Subsystem { |
| 14 | public static double driveP = 0.008, driveI = 0.001, driveD = -0.002; |
| 15 | public static double defaultGyroP = 0.006, defaultGyroI = 0.00000, |
| 16 | defaultGyroD = -0.000; |
| 17 | private double gyroZero = 0; |
| 18 | |
| 19 | public static final double WHEEL_DIAMETER = 6; // inches |
| 20 | public static final int ENCODER_PULSES_PER_REVOLUTION = 256; |
| 21 | public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI |
| 22 | / ENCODER_PULSES_PER_REVOLUTION; |
| 23 | |
| 24 | private static DriveTrain driveTrain; |
| 25 | private final CANTalon frontLeft, frontRight, rearLeft, rearRight; |
| 26 | private final RobotDrive robotDrive; |
| 27 | private final Encoder leftEncoder, rightEncoder; |
| 28 | |
| 29 | private ADXRS450_Gyro imu; |
| 30 | |
| 31 | private DriveTrain() { |
| 32 | // MOTOR CONTROLLERS |
| 33 | frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); |
| 34 | frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); |
| 35 | rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); |
| 36 | rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); |
| 37 | |
| 38 | // ENCODERS |
| 39 | leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, |
| 40 | Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X); |
| 41 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, |
| 42 | Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X); |
| 43 | |
| 44 | leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
| 45 | rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
| 46 | |
| 47 | // ROBOT DRIVE |
| 48 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); |
| 49 | |
| 50 | this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT); |
| 51 | } |
| 52 | |
| 53 | public static DriveTrain getDriveTrain() { |
| 54 | if (driveTrain == null) { |
| 55 | driveTrain = new DriveTrain(); |
| 56 | } |
| 57 | return driveTrain; |
| 58 | } |
| 59 | |
| 60 | // DRIVE METHODS |
| 61 | public void setMotorValues(final double left, final double right) { |
| 62 | frontLeft.set(left); |
| 63 | rearLeft.set(left); |
| 64 | |
| 65 | frontRight.set(-right); |
| 66 | rearRight.set(-right); |
| 67 | } |
| 68 | |
| 69 | public void joystickDrive(final double thrust, final double twist) { |
| 70 | robotDrive.arcadeDrive(thrust, twist, true); |
| 71 | } |
| 72 | |
| 73 | public void stop() { |
| 74 | setMotorValues(0, 0); |
| 75 | } |
| 76 | |
| 77 | public double getLeftMotorVal() { |
| 78 | return (frontLeft.get() + rearLeft.get()) / 2; |
| 79 | } |
| 80 | |
| 81 | public double getRightMotorVal() { |
| 82 | return (frontRight.get() + rearRight.get()) / 2; |
| 83 | } |
| 84 | |
| 85 | // ENCODER METHODS |
| 86 | |
| 87 | public double getLeftEncoderDistance() { |
| 88 | return leftEncoder.getDistance(); |
| 89 | } |
| 90 | |
| 91 | public double getRightEncoderDistance() { |
| 92 | return rightEncoder.getDistance(); |
| 93 | } |
| 94 | |
| 95 | public void printEncoderOutput() { |
| 96 | // System.out.println("left: " + getLeftEncoderDistance()); |
| 97 | // System.out.println("right: " + getRightEncoderDistance()); |
| 98 | System.out.println(getAvgEncoderDistance()); |
| 99 | } |
| 100 | |
| 101 | public double getAvgEncoderDistance() { |
| 102 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; |
| 103 | } |
| 104 | |
| 105 | public void resetEncoders() { |
| 106 | leftEncoder.reset(); |
| 107 | rightEncoder.reset(); |
| 108 | } |
| 109 | |
| 110 | public double getLeftSpeed() { |
| 111 | return leftEncoder.getRate(); |
| 112 | } |
| 113 | |
| 114 | public double getRightSpeed() { |
| 115 | return rightEncoder.getRate(); |
| 116 | } |
| 117 | |
| 118 | public double getSpeed() { |
| 119 | return (getLeftSpeed() + getRightSpeed()) / 2.0; |
| 120 | } |
| 121 | |
| 122 | // ------Gyro------// |
| 123 | public double getAngle() { |
| 124 | return this.imu.getAngle() - this.gyroZero; |
| 125 | } |
| 126 | |
| 127 | public void resetGyro() { |
| 128 | this.gyroZero = this.getAngle(); |
| 129 | } |
| 130 | |
| 131 | public double getZeroAngle() { |
| 132 | return this.gyroZero; |
| 133 | } |
| 134 | |
| 135 | @Override |
| 136 | protected void initDefaultCommand() { |
| 137 | setDefaultCommand(new JoystickDrive()); |
| 138 | } |
| 139 | |
| 140 | } |