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