Commit | Line | Data |
---|---|---|
38a404b3 KZ |
1 | package org.usfirst.frc.team3501.robot.subsystems; |
2 | ||
3 | import org.usfirst.frc.team3501.robot.Constants; | |
5483fde9 | 4 | import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; |
06df4cd4 | 5 | import org.usfirst.frc.team3501.robot.utils.PIDController; |
04f2cb52 | 6 | |
a1c76caf CZ |
7 | import com.ctre.CANTalon; |
8 | ||
bf921ece | 9 | import edu.wpi.first.wpilibj.ADXRS450_Gyro; |
4a75c629 | 10 | import edu.wpi.first.wpilibj.DoubleSolenoid; |
73e8adbc | 11 | import edu.wpi.first.wpilibj.DoubleSolenoid.Value; |
fa4e4a97 | 12 | import edu.wpi.first.wpilibj.Encoder; |
ccbc35ae | 13 | import edu.wpi.first.wpilibj.RobotDrive; |
38a404b3 KZ |
14 | import edu.wpi.first.wpilibj.command.Subsystem; |
15 | ||
16 | public class DriveTrain extends Subsystem { | |
34ffcd03 | 17 | public static double driveP, driveI, driveD; |
542234fe | 18 | public static double turnP, turnI, turnD; |
c846487e | 19 | public static double driveStraightGyroP = 0.01; |
e12d6901 | 20 | |
665abef7 MW |
21 | public static final String DRIVE_P_Val = "DriveP"; |
22 | public static final String DRIVE_I_Val = "DriveI"; | |
23 | public static final String DRIVE_D_Val = "DriveD"; | |
24 | public static final String DRIVE_TARGET_DIST = "SET_DIST"; | |
25 | public static final String DRIVE_MOTOR_VAL = "SPEED"; | |
26 | public static final String GYRO_P_Val = "GyroP"; | |
27 | public static final String GYRO_I_Val = "GyroI"; | |
28 | public static final String GYRO_D_Val = "GyroD"; | |
29 | public static final String GYRO_TARGET_ANGLE = "SET_ANGLE"; | |
30 | public static final int PID_ERROR = -1; | |
31 | public static final int TARGET_DISTANCE_ERROR = -1; | |
32 | ||
b634ebbc CZ |
33 | public static final double WHEEL_DIAMETER = 6; // inches |
34 | public static final int ENCODER_PULSES_PER_REVOLUTION = 256; | |
35 | public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI | |
36 | / ENCODER_PULSES_PER_REVOLUTION; | |
9dc69158 CZ |
37 | |
38 | public static final double MAINTAIN_CLIMBED_POSITION = 0; | |
39 | public static final double TIME_TO_CLIMB_FOR = 0; | |
40 | public static final double CLIMBER_SPEED = 0; | |
41 | ||
cc42bd52 | 42 | private static DriveTrain driveTrain; |
b8791ca4 | 43 | |
cc42bd52 ME |
44 | private final CANTalon frontLeft, frontRight, rearLeft, rearRight; |
45 | private final RobotDrive robotDrive; | |
46 | private final Encoder leftEncoder, rightEncoder; | |
73e8adbc | 47 | private final DoubleSolenoid leftGearPiston, rightGearPiston; |
cc42bd52 | 48 | |
bf921ece | 49 | private ADXRS450_Gyro imu; |
e12d6901 | 50 | |
366f1cfd | 51 | public boolean shouldBeClimbing = false; |
cef1f36d | 52 | |
06df4cd4 | 53 | private PIDController driveController; |
01ea2879 | 54 | private PIDController gyroController; |
06df4cd4 | 55 | |
ffb43c5c | 56 | private boolean isClimbing; |
06df4cd4 | 57 | |
0c15b549 | 58 | private DriveTrain() { |
06df4cd4 | 59 | |
63c60c71 | 60 | // PID TUNING |
0c15b549 | 61 | driveController = new PIDController(driveP, driveI, driveD); |
d3ed4499 | 62 | gyroController = new PIDController(turnP, turnI, turnD); |
63c60c71 | 63 | |
40d69167 MW |
64 | // PID TUNING |
65 | ||
66 | public static final String DRIVE_P_Val = "DriveP"; | |
67 | public static final String DRIVE_I_Val = "DriveI"; | |
68 | public static final String DRIVE_D_Val = "DriveD"; | |
69 | public static final String DRIVE_TARGET_DIST = "SET_DIST"; | |
70 | public static final String DRIVE_MOTOR_VAL = "SPEED"; | |
71 | public static final String GYRO_P_Val = "GyroP"; | |
72 | public static final String GYRO_I_Val = "GyroI"; | |
73 | public static final String GYRO_D_Val = "GyroD"; | |
74 | public static final String GYRO_TARGET_ANGLE = "SET_ANGLE"; | |
75 | public static final int PID_ERROR = -1; | |
76 | public static final int TARGET_DISTANCE_ERROR = -1; | |
77 | ||
cc42bd52 ME |
78 | // MOTOR CONTROLLERS |
79 | frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); | |
80 | frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); | |
81 | rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); | |
82 | rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); | |
83 | ||
84 | // ENCODERS | |
85 | leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, | |
3e2738c4 | 86 | Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 87 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, |
3e2738c4 | 88 | Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X); |
cc42bd52 | 89 | |
b634ebbc CZ |
90 | leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); |
91 | rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); | |
cc42bd52 ME |
92 | |
93 | // ROBOT DRIVE | |
94 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); | |
8e4c083c | 95 | |
bf921ece | 96 | this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT); |
af4491f7 | 97 | |
ca372ce8 | 98 | // TODO: Not sure if MODULE_NUMBER should be the same for both |
58bcc21d | 99 | leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE, |
ca372ce8 AD |
100 | Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD, |
101 | Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE); | |
58bcc21d | 102 | rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE, |
ca372ce8 AD |
103 | Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD, |
104 | Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE); | |
cc42bd52 ME |
105 | } |
106 | ||
06df4cd4 E |
107 | public PIDController getDriveController() { |
108 | return this.driveController; | |
109 | } | |
110 | ||
90b435ce ES |
111 | public PIDController getGyroController() { |
112 | return this.gyroController; | |
113 | } | |
114 | ||
cc42bd52 ME |
115 | public static DriveTrain getDriveTrain() { |
116 | if (driveTrain == null) { | |
117 | driveTrain = new DriveTrain(); | |
118 | } | |
119 | return driveTrain; | |
120 | } | |
121 | ||
122 | // DRIVE METHODS | |
123 | public void setMotorValues(final double left, final double right) { | |
124 | frontLeft.set(left); | |
125 | rearLeft.set(left); | |
126 | ||
b081e34b ME |
127 | frontRight.set(-right); |
128 | rearRight.set(-right); | |
cc42bd52 ME |
129 | } |
130 | ||
131 | public void joystickDrive(final double thrust, final double twist) { | |
b081e34b | 132 | robotDrive.arcadeDrive(thrust, twist, true); |
cc42bd52 ME |
133 | } |
134 | ||
135 | public void stop() { | |
136 | setMotorValues(0, 0); | |
137 | } | |
138 | ||
f0a71840 CZ |
139 | public double getLeftMotorVal() { |
140 | return (frontLeft.get() + rearLeft.get()) / 2; | |
cc42bd52 ME |
141 | } |
142 | ||
f0a71840 CZ |
143 | public double getRightMotorVal() { |
144 | return (frontRight.get() + rearRight.get()) / 2; | |
cc42bd52 ME |
145 | } |
146 | ||
cc42bd52 ME |
147 | // ENCODER METHODS |
148 | ||
3a5d9ac7 | 149 | public double getLeftEncoderDistance() { |
cc42bd52 ME |
150 | return leftEncoder.getDistance(); |
151 | } | |
152 | ||
3a5d9ac7 | 153 | public double getRightEncoderDistance() { |
cc42bd52 ME |
154 | return rightEncoder.getDistance(); |
155 | } | |
156 | ||
8e4c083c | 157 | public void printEncoderOutput() { |
174f415c CZ |
158 | System.out.println("left: " + getLeftEncoderDistance()); |
159 | System.out.println("right: " + getRightEncoderDistance()); | |
c846487e | 160 | // System.out.println(getAvgEncoderDistance()); |
8e4c083c CZ |
161 | } |
162 | ||
cc42bd52 ME |
163 | public double getAvgEncoderDistance() { |
164 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; | |
165 | } | |
166 | ||
167 | public void resetEncoders() { | |
168 | leftEncoder.reset(); | |
169 | rightEncoder.reset(); | |
170 | } | |
171 | ||
172 | public double getLeftSpeed() { | |
173 | return leftEncoder.getRate(); | |
174 | } | |
175 | ||
176 | public double getRightSpeed() { | |
177 | return rightEncoder.getRate(); | |
178 | } | |
179 | ||
180 | public double getSpeed() { | |
181 | return (getLeftSpeed() + getRightSpeed()) / 2.0; | |
182 | } | |
183 | ||
e12d6901 CZ |
184 | // ------Gyro------// |
185 | public double getAngle() { | |
c846487e | 186 | return this.imu.getAngle(); |
e12d6901 CZ |
187 | } |
188 | ||
189 | public void resetGyro() { | |
571fb5c9 | 190 | this.imu.reset(); |
e12d6901 CZ |
191 | } |
192 | ||
73e8adbc AD |
193 | /* |
194 | * @return a value that is the current setpoint for the piston kReverse or | |
195 | * KForward | |
196 | */ | |
06415bd8 | 197 | public Value getLeftGearPistonValue() { |
73e8adbc AD |
198 | return leftGearPiston.get(); |
199 | } | |
200 | ||
06415bd8 AD |
201 | /* |
202 | * @return a value that is the current setpoint for the piston kReverse or | |
203 | * KForward | |
204 | */ | |
205 | public Value getRightGearPistonValue() { | |
206 | return rightGearPiston.get(); | |
207 | } | |
208 | ||
73e8adbc AD |
209 | /* |
210 | * Changes the ball shift gear assembly to high | |
211 | */ | |
212 | public void setHighGear() { | |
213 | changeGear(Constants.DriveTrain.HIGH_GEAR); | |
214 | } | |
215 | ||
216 | /* | |
217 | * Changes the ball shift gear assembly to low | |
218 | */ | |
219 | public void setLowGear() { | |
220 | changeGear(Constants.DriveTrain.LOW_GEAR); | |
221 | } | |
222 | ||
223 | /* | |
224 | * Changes the gear to a DoubleSolenoid.Value | |
225 | */ | |
226 | private void changeGear(DoubleSolenoid.Value gear) { | |
227 | leftGearPiston.set(gear); | |
228 | rightGearPiston.set(gear); | |
e12d6901 CZ |
229 | } |
230 | ||
cc42bd52 ME |
231 | @Override |
232 | protected void initDefaultCommand() { | |
233 | setDefaultCommand(new JoystickDrive()); | |
234 | } | |
38a404b3 | 235 | } |