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