| 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.DoubleSolenoid; |
| 10 | import edu.wpi.first.wpilibj.DoubleSolenoid.Value; |
| 11 | import edu.wpi.first.wpilibj.Encoder; |
| 12 | import edu.wpi.first.wpilibj.RobotDrive; |
| 13 | import edu.wpi.first.wpilibj.command.Subsystem; |
| 14 | |
| 15 | public class DriveTrain extends Subsystem { |
| 16 | public static double driveP = 0.006, driveI = 0.001, driveD = -0.002; |
| 17 | public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005; |
| 18 | public static double driveStraightGyroP = 0.01; |
| 19 | |
| 20 | public static final double WHEEL_DIAMETER = 6; // inches |
| 21 | public static final int ENCODER_PULSES_PER_REVOLUTION = 256; |
| 22 | public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI |
| 23 | / ENCODER_PULSES_PER_REVOLUTION; |
| 24 | public static final int MAINTAIN_CLIMBED_POSITION = 0; |
| 25 | public static final int TIME_TO_CLIMB_FOR = 0; |
| 26 | private static DriveTrain driveTrain; |
| 27 | |
| 28 | private final CANTalon frontLeft, frontRight, rearLeft, rearRight; |
| 29 | private final RobotDrive robotDrive; |
| 30 | private final Encoder leftEncoder, rightEncoder; |
| 31 | private final DoubleSolenoid leftGearPiston, rightGearPiston; |
| 32 | |
| 33 | private ADXRS450_Gyro imu; |
| 34 | |
| 35 | private DriveTrain() { |
| 36 | // MOTOR CONTROLLERS |
| 37 | frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); |
| 38 | frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); |
| 39 | rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); |
| 40 | rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); |
| 41 | |
| 42 | // ENCODERS |
| 43 | leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, |
| 44 | Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X); |
| 45 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, |
| 46 | Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X); |
| 47 | |
| 48 | leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
| 49 | rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
| 50 | |
| 51 | // ROBOT DRIVE |
| 52 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); |
| 53 | |
| 54 | this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT); |
| 55 | |
| 56 | // TODO: Not sure if MODULE_NUMBER should be the same for both |
| 57 | leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER, |
| 58 | Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD, |
| 59 | Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE); |
| 60 | rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER, |
| 61 | Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD, |
| 62 | Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE); |
| 63 | } |
| 64 | |
| 65 | public static DriveTrain getDriveTrain() { |
| 66 | if (driveTrain == null) { |
| 67 | driveTrain = new DriveTrain(); |
| 68 | } |
| 69 | return driveTrain; |
| 70 | } |
| 71 | |
| 72 | // DRIVE METHODS |
| 73 | public void setMotorValues(final double left, final double right) { |
| 74 | frontLeft.set(left); |
| 75 | rearLeft.set(left); |
| 76 | |
| 77 | frontRight.set(-right); |
| 78 | rearRight.set(-right); |
| 79 | } |
| 80 | |
| 81 | public void joystickDrive(final double thrust, final double twist) { |
| 82 | robotDrive.arcadeDrive(thrust, twist, true); |
| 83 | } |
| 84 | |
| 85 | public void stop() { |
| 86 | setMotorValues(0, 0); |
| 87 | } |
| 88 | |
| 89 | public double getLeftMotorVal() { |
| 90 | return (frontLeft.get() + rearLeft.get()) / 2; |
| 91 | } |
| 92 | |
| 93 | public double getRightMotorVal() { |
| 94 | return (frontRight.get() + rearRight.get()) / 2; |
| 95 | } |
| 96 | |
| 97 | // ENCODER METHODS |
| 98 | |
| 99 | public double getLeftEncoderDistance() { |
| 100 | return leftEncoder.getDistance(); |
| 101 | } |
| 102 | |
| 103 | public double getRightEncoderDistance() { |
| 104 | return rightEncoder.getDistance(); |
| 105 | } |
| 106 | |
| 107 | public void printEncoderOutput() { |
| 108 | System.out.println("left: " + getLeftEncoderDistance()); |
| 109 | System.out.println("right: " + getRightEncoderDistance()); |
| 110 | // System.out.println(getAvgEncoderDistance()); |
| 111 | } |
| 112 | |
| 113 | public double getAvgEncoderDistance() { |
| 114 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; |
| 115 | } |
| 116 | |
| 117 | public void resetEncoders() { |
| 118 | leftEncoder.reset(); |
| 119 | rightEncoder.reset(); |
| 120 | } |
| 121 | |
| 122 | public double getLeftSpeed() { |
| 123 | return leftEncoder.getRate(); |
| 124 | } |
| 125 | |
| 126 | public double getRightSpeed() { |
| 127 | return rightEncoder.getRate(); |
| 128 | } |
| 129 | |
| 130 | public double getSpeed() { |
| 131 | return (getLeftSpeed() + getRightSpeed()) / 2.0; |
| 132 | } |
| 133 | |
| 134 | // ------Gyro------// |
| 135 | public double getAngle() { |
| 136 | return this.imu.getAngle(); |
| 137 | } |
| 138 | |
| 139 | public void resetGyro() { |
| 140 | this.imu.reset(); |
| 141 | } |
| 142 | |
| 143 | /* |
| 144 | * @return a value that is the current setpoint for the piston kReverse or |
| 145 | * KForward |
| 146 | */ |
| 147 | public Value getLeftGearPistonValue() { |
| 148 | return leftGearPiston.get(); |
| 149 | } |
| 150 | |
| 151 | /* |
| 152 | * @return a value that is the current setpoint for the piston kReverse or |
| 153 | * KForward |
| 154 | */ |
| 155 | public Value getRightGearPistonValue() { |
| 156 | return rightGearPiston.get(); |
| 157 | } |
| 158 | |
| 159 | /* |
| 160 | * Changes the ball shift gear assembly to high |
| 161 | */ |
| 162 | public void setHighGear() { |
| 163 | changeGear(Constants.DriveTrain.HIGH_GEAR); |
| 164 | } |
| 165 | |
| 166 | /* |
| 167 | * Changes the ball shift gear assembly to low |
| 168 | */ |
| 169 | public void setLowGear() { |
| 170 | changeGear(Constants.DriveTrain.LOW_GEAR); |
| 171 | } |
| 172 | |
| 173 | /* |
| 174 | * Changes the gear to a DoubleSolenoid.Value |
| 175 | */ |
| 176 | private void changeGear(DoubleSolenoid.Value gear) { |
| 177 | leftGearPiston.set(gear); |
| 178 | rightGearPiston.set(gear); |
| 179 | } |
| 180 | |
| 181 | @Override |
| 182 | protected void initDefaultCommand() { |
| 183 | setDefaultCommand(new JoystickDrive()); |
| 184 | } |
| 185 | |
| 186 | } |