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