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