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