Commit | Line | Data |
---|---|---|
38a404b3 KZ |
1 | package org.usfirst.frc.team3501.robot.subsystems; |
2 | ||
3 | import org.usfirst.frc.team3501.robot.Constants; | |
33141cdd KZ |
4 | import org.usfirst.frc.team3501.robot.GyroLib; |
5 | import org.usfirst.frc.team3501.robot.MathLib; | |
6 | import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; | |
111dc444 | 7 | |
38a404b3 | 8 | import edu.wpi.first.wpilibj.CANTalon; |
111dc444 | 9 | import edu.wpi.first.wpilibj.CounterBase.EncodingType; |
d9c04720 | 10 | import edu.wpi.first.wpilibj.DoubleSolenoid; |
2aea5cc2 | 11 | import edu.wpi.first.wpilibj.DoubleSolenoid.Value; |
111dc444 | 12 | import edu.wpi.first.wpilibj.Encoder; |
b54ad73b | 13 | import edu.wpi.first.wpilibj.I2C; |
33141cdd KZ |
14 | import edu.wpi.first.wpilibj.RobotDrive; |
15 | import edu.wpi.first.wpilibj.command.PIDSubsystem; | |
16 | ||
17 | public class DriveTrain extends PIDSubsystem { | |
1c94f230 KZ |
18 | // Encoder PID Proportional Constants P, I, and D |
19 | private static double EP = 0.013, EI = 0.000015, ED = -0.002; | |
20 | ||
21 | // Gyro PID Constants P, I, and D | |
22 | private static double GP = 0.018, GI = 0.000015, GD = 0; | |
33141cdd | 23 | private static double pidOutput = 0; |
1c94f230 KZ |
24 | |
25 | // PID Controller tolerances for the error | |
33141cdd | 26 | private static double encoderTolerance = 8.0, gyroTolerance = 5.0; |
1c94f230 KZ |
27 | |
28 | // Current Drive Mode Default Drive Mode is Manual | |
33141cdd KZ |
29 | private int DRIVE_MODE = 1; |
30 | ||
1c94f230 | 31 | // Different Drive Modes |
33141cdd | 32 | private static final int MANUAL_MODE = 1, ENCODER_MODE = 2, GYRO_MODE = 3; |
38a404b3 | 33 | |
1884c3cf | 34 | private Encoder leftEncoder, rightEncoder; |
d7bf2340 | 35 | private CANTalon frontLeft, frontRight, rearLeft, rearRight; |
33141cdd KZ |
36 | private RobotDrive robotDrive; |
37 | ||
38 | private GyroLib gyro; | |
d9c04720 | 39 | private DoubleSolenoid leftGearPiston, rightGearPiston; |
71d73690 | 40 | |
d7bf2340 | 41 | public DriveTrain() { |
1c94f230 | 42 | super(EP, EI, ED); |
33141cdd | 43 | |
d7bf2340 KZ |
44 | frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); |
45 | frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); | |
46 | rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); | |
47 | rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); | |
1884c3cf | 48 | |
33141cdd | 49 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); |
d7bf2340 KZ |
50 | leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, |
51 | Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X); | |
52 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, | |
53 | Constants.DriveTrain.ENCODER_RIGHT_B, false, EncodingType.k4X); | |
45bdf5b9 KZ |
54 | leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); |
55 | rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); | |
33141cdd KZ |
56 | |
57 | leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); | |
58 | rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); | |
59 | ||
60 | gyro = new GyroLib(I2C.Port.kOnboard, false); | |
61 | ||
62 | DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE; | |
63 | setEncoderPID(); | |
64 | this.disable(); | |
65 | gyro.start(); | |
d004deee | 66 | |
d9c04720 | 67 | leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.LEFT_FORWARD, |
1c94f230 | 68 | Constants.DriveTrain.LEFT_REVERSE); |
d9c04720 SC |
69 | rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.RIGHT_FORWARD, |
70 | Constants.DriveTrain.RIGHT_REVERSE); | |
54c588d9 | 71 | Constants.DriveTrain.inverted = false; |
d7bf2340 KZ |
72 | } |
73 | ||
74 | @Override | |
75 | protected void initDefaultCommand() { | |
33141cdd KZ |
76 | setDefaultCommand(new JoystickDrive()); |
77 | } | |
78 | ||
1c94f230 | 79 | // Print tne PID Output |
33141cdd KZ |
80 | public void printOutput() { |
81 | System.out.println("PIDOutput: " + pidOutput); | |
82 | } | |
83 | ||
84 | private double getAvgEncoderDistance() { | |
85 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; | |
86 | } | |
87 | ||
1c94f230 KZ |
88 | // Whether or not the PID Controller thinks we have reached the target |
89 | // setpoint | |
33141cdd KZ |
90 | public boolean reachedTarget() { |
91 | if (this.onTarget()) { | |
92 | this.disable(); | |
93 | return true; | |
94 | } else { | |
95 | return false; | |
96 | } | |
97 | } | |
98 | ||
99 | public void stop() { | |
100 | drive(0, 0); | |
d7bf2340 KZ |
101 | } |
102 | ||
103 | public void resetEncoders() { | |
104 | leftEncoder.reset(); | |
105 | rightEncoder.reset(); | |
106 | } | |
107 | ||
d7bf2340 | 108 | public double getRightSpeed() { |
6833a887 | 109 | return rightEncoder.getRate(); // in inches per second |
d7bf2340 KZ |
110 | } |
111 | ||
112 | public double getLeftSpeed() { | |
6833a887 | 113 | return leftEncoder.getRate(); // in inches per second |
d7bf2340 KZ |
114 | } |
115 | ||
116 | public double getSpeed() { | |
6833a887 | 117 | return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second |
d7bf2340 KZ |
118 | } |
119 | ||
d7bf2340 | 120 | public double getRightDistance() { |
6833a887 | 121 | return rightEncoder.getDistance(); // in inches |
d7bf2340 KZ |
122 | } |
123 | ||
d7bf2340 | 124 | public double getLeftDistance() { |
6833a887 | 125 | return leftEncoder.getDistance(); // in inches |
d7bf2340 KZ |
126 | } |
127 | ||
1c94f230 KZ |
128 | // Get error between the setpoint of PID Controller and the current state of |
129 | // the robot | |
33141cdd KZ |
130 | public double getError() { |
131 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) | |
132 | return Math.abs(this.getSetpoint() - getAvgEncoderDistance()); | |
133 | else | |
134 | return Math.abs(this.getSetpoint() + getGyroAngle()); | |
d7bf2340 KZ |
135 | } |
136 | ||
33141cdd KZ |
137 | public double getGyroAngle() { |
138 | return gyro.getRotationZ().getAngle(); | |
139 | } | |
140 | ||
141 | public void resetGyro() { | |
142 | gyro.reset(); | |
143 | } | |
144 | ||
145 | public void printEncoder(int i, int n) { | |
146 | if (i % n == 0) { | |
147 | System.out.println("Left: " + this.getLeftDistance()); | |
148 | System.out.println("Right: " + this.getRightDistance()); | |
149 | ||
150 | } | |
151 | } | |
152 | ||
153 | public void printGyroOutput() { | |
154 | System.out.println("Gyro Angle" + -this.getGyroAngle()); | |
155 | } | |
156 | ||
1c94f230 KZ |
157 | /* |
158 | * returns the PID output that is returned by the PID Controller | |
159 | */ | |
33141cdd KZ |
160 | public double getOutput() { |
161 | return pidOutput; | |
162 | } | |
163 | ||
1c94f230 | 164 | // Updates the PID constants based on which control mode is being used |
33141cdd KZ |
165 | public void updatePID() { |
166 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) | |
1c94f230 | 167 | this.getPIDController().setPID(EP, EI, ED); |
33141cdd | 168 | else |
1c94f230 | 169 | this.getPIDController().setPID(GP, GD, GI); |
33141cdd KZ |
170 | } |
171 | ||
172 | public CANTalon getFrontLeft() { | |
173 | return frontLeft; | |
174 | } | |
175 | ||
176 | public CANTalon getFrontRight() { | |
177 | return frontRight; | |
178 | } | |
179 | ||
180 | public CANTalon getRearLeft() { | |
181 | return rearLeft; | |
182 | } | |
183 | ||
184 | public CANTalon getRearRight() { | |
185 | return rearRight; | |
186 | } | |
187 | ||
188 | public int getMode() { | |
189 | return DRIVE_MODE; | |
190 | } | |
191 | ||
1c94f230 KZ |
192 | /* |
193 | * Method is a required method that the PID Subsystem uses to return the | |
194 | * calculated PID value to the driver | |
195 | * | |
196 | * @param Gives the user the output from the PID algorithm that is calculated | |
197 | * internally | |
198 | * | |
199 | * Body: Uses the output, does some filtering and drives the robot | |
200 | */ | |
33141cdd KZ |
201 | @Override |
202 | protected void usePIDOutput(double output) { | |
203 | double left = 0; | |
204 | double right = 0; | |
205 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) { | |
206 | double drift = this.getLeftDistance() - this.getRightDistance(); | |
207 | if (Math.abs(output) > 0 && Math.abs(output) < 0.3) | |
208 | output = Math.signum(output) * 0.3; | |
209 | left = output; | |
1c94f230 | 210 | right = output + drift * EP / 10; |
33141cdd KZ |
211 | } |
212 | else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) { | |
213 | left = output; | |
214 | right = -output; | |
215 | } | |
216 | drive(left, right); | |
217 | pidOutput = output; | |
d7bf2340 KZ |
218 | } |
219 | ||
33141cdd KZ |
220 | @Override |
221 | protected double returnPIDInput() { | |
222 | return sensorFeedback(); | |
d7bf2340 | 223 | } |
33141cdd | 224 | |
1c94f230 KZ |
225 | /* |
226 | * Checks the drive mode | |
227 | * | |
228 | * @return the current state of the robot in each state | |
229 | * Average distance from both sides of tank drive for Encoder Mode | |
230 | * Angle from the gyro in GYRO_MODE | |
231 | */ | |
33141cdd KZ |
232 | private double sensorFeedback() { |
233 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) | |
234 | return getAvgEncoderDistance(); | |
235 | else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) | |
236 | return -this.getGyroAngle(); | |
237 | // counterclockwise is positive on joystick but we want it to be negative | |
238 | else | |
239 | return 0; | |
240 | } | |
241 | ||
1c94f230 KZ |
242 | /* |
243 | * @param left and right setpoints to set to the left and right side of tank | |
244 | * inverted is for Logan, wants the robot to invert all controls left = right | |
245 | * and right = left | |
246 | * negative input is required for the regular rotation because RobotDrive | |
247 | * tankdrive method drives inverted | |
248 | */ | |
33141cdd | 249 | public void drive(double left, double right) { |
33141cdd | 250 | // dunno why but inverted drive (- values is forward) |
54c588d9 CZ |
251 | if (!Constants.DriveTrain.inverted) |
252 | robotDrive.tankDrive(-left, | |
253 | -right); | |
254 | else | |
255 | robotDrive.tankDrive(right, left); | |
33141cdd KZ |
256 | } |
257 | ||
1c94f230 KZ |
258 | /* |
259 | * constrains the distance to within -100 and 100 since we aren't going to | |
260 | * drive more than 100 inches | |
261 | * | |
262 | * Configure Encoder PID | |
263 | * | |
264 | * Sets the setpoint to the PID subsystem | |
265 | */ | |
33141cdd KZ |
266 | public void driveDistance(double dist, double maxTimeOut) { |
267 | dist = MathLib.constrain(dist, -100, 100); | |
268 | setEncoderPID(); | |
269 | setSetpoint(dist); | |
270 | } | |
271 | ||
1c94f230 KZ |
272 | /* |
273 | * Sets the encoder mode | |
274 | * Updates the PID constants sets the tolerance and sets output/input ranges | |
275 | * Enables the PID controllers | |
276 | */ | |
33141cdd KZ |
277 | public void setEncoderPID() { |
278 | DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE; | |
279 | this.updatePID(); | |
280 | this.setAbsoluteTolerance(encoderTolerance); | |
281 | this.setOutputRange(-1.0, 1.0); | |
282 | this.setInputRange(-200.0, 200.0); | |
283 | this.enable(); | |
284 | } | |
285 | ||
1c94f230 KZ |
286 | /* |
287 | * Sets the Gyro Mode | |
288 | * Updates the PID constants, sets the tolerance and sets output/input ranges | |
289 | * Enables the PID controllers | |
290 | */ | |
33141cdd KZ |
291 | private void setGyroPID() { |
292 | DRIVE_MODE = Constants.DriveTrain.GYRO_MODE; | |
293 | this.updatePID(); | |
1c94f230 | 294 | this.getPIDController().setPID(GP, GI, GD); |
33141cdd KZ |
295 | |
296 | this.setAbsoluteTolerance(gyroTolerance); | |
297 | this.setOutputRange(-1.0, 1.0); | |
298 | this.setInputRange(-360.0, 360.0); | |
299 | this.enable(); | |
300 | } | |
301 | ||
1c94f230 KZ |
302 | /* |
303 | * Turning method that should be used repeatedly in a command | |
304 | * | |
305 | * First constrains the angle to within -360 and 360 since that is as much as | |
306 | * we need to turn | |
307 | * | |
308 | * Configures Gyro PID and sets the setpoint as an angle | |
309 | */ | |
33141cdd KZ |
310 | public void turnAngle(double angle) { |
311 | angle = MathLib.constrain(angle, -360, 360); | |
312 | setGyroPID(); | |
313 | setSetpoint(angle); | |
314 | } | |
315 | ||
316 | public void setMotorSpeeds(double left, double right) { | |
317 | // positive setpoint to left side makes it go backwards | |
318 | // positive setpoint to right side makes it go forwards. | |
319 | frontLeft.set(-left); | |
320 | rearLeft.set(-left); | |
321 | frontRight.set(right); | |
322 | rearRight.set(right); | |
323 | } | |
324 | ||
1c94f230 KZ |
325 | /* |
326 | * @return a value that is the current setpoint for the piston | |
327 | * kReverse or kForward | |
328 | */ | |
2a099bc6 KZ |
329 | public Value getLeftGearPistonValue() { |
330 | return leftGearPiston.get(); | |
331 | } | |
332 | ||
1c94f230 KZ |
333 | /* |
334 | * @return a value that is the current setpoint for the piston | |
335 | * kReverse or kForward | |
336 | */ | |
2a099bc6 KZ |
337 | public Value getRightGearPistonValue() { |
338 | return rightGearPiston.get(); | |
339 | } | |
340 | ||
1c94f230 KZ |
341 | /* |
342 | * Changes the ball shift gear assembly to high | |
343 | */ | |
2a099bc6 KZ |
344 | public void setHighGear() { |
345 | changeGear(Constants.DriveTrain.HIGH_GEAR); | |
346 | } | |
347 | ||
1c94f230 KZ |
348 | /* |
349 | * Changes the ball shift gear assembly to low | |
350 | */ | |
2a099bc6 KZ |
351 | public void setLowGear() { |
352 | changeGear(Constants.DriveTrain.LOW_GEAR); | |
353 | } | |
354 | ||
1c94f230 KZ |
355 | /* |
356 | * changes the gear to a DoubleSolenoid.Value | |
357 | */ | |
2a099bc6 KZ |
358 | public void changeGear(DoubleSolenoid.Value gear) { |
359 | leftGearPiston.set(gear); | |
360 | rightGearPiston.set(gear); | |
361 | } | |
38a404b3 | 362 | } |