add code for switching b/w cameras
[3501/stronghold-2016] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
CommitLineData
38a404b3
KZ
1package org.usfirst.frc.team3501.robot.subsystems;
2
d9475515 3import org.usfirst.frc.team3501.robot.CheesyDriveHelper;
38a404b3 4import org.usfirst.frc.team3501.robot.Constants;
33141cdd 5import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
111dc444 6
38a404b3 7import edu.wpi.first.wpilibj.CANTalon;
111dc444 8import edu.wpi.first.wpilibj.CounterBase.EncodingType;
d9c04720 9import edu.wpi.first.wpilibj.DoubleSolenoid;
2aea5cc2 10import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
111dc444 11import edu.wpi.first.wpilibj.Encoder;
33141cdd
KZ
12import edu.wpi.first.wpilibj.RobotDrive;
13import edu.wpi.first.wpilibj.command.PIDSubsystem;
14
15public class DriveTrain extends PIDSubsystem {
8d270bbc 16 // Determines if the "front" of the robot has been reversed
571a0e2a 17 private boolean outputFlipped = false;
8d270bbc 18
fb75626b 19 private static double pidOutput = 0;
38a404b3 20
1884c3cf 21 private Encoder leftEncoder, rightEncoder;
96215d97 22
d7bf2340 23 private CANTalon frontLeft, frontRight, rearLeft, rearRight;
33141cdd
KZ
24 private RobotDrive robotDrive;
25
d9c04720 26 private DoubleSolenoid leftGearPiston, rightGearPiston;
fb75626b 27
d9475515
HD
28 private CheesyDriveHelper cheese;
29
9e65c056
ME
30 // Drivetrain specific constants that relate to the inches per pulse value for
31 // the encoders
71d73690 32
d7bf2340 33 public DriveTrain() {
fb75626b
KZ
34 super(Constants.DriveTrain.kp, Constants.DriveTrain.ki,
35 Constants.DriveTrain.kd);
33141cdd 36
e1f7a742
HD
37 frontLeft = new CANTalon(Constants.DriveTrain.DRIVE_FRONT_LEFT);
38 frontRight = new CANTalon(Constants.DriveTrain.DRIVE_FRONT_RIGHT);
39 rearLeft = new CANTalon(Constants.DriveTrain.DRIVE_REAR_LEFT);
40 rearRight = new CANTalon(Constants.DriveTrain.DRIVE_REAR_RIGHT);
1884c3cf 41
33141cdd 42 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
96215d97 43
d7bf2340
KZ
44 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
45 Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X);
46 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
47 Constants.DriveTrain.ENCODER_RIGHT_B, false, EncodingType.k4X);
45bdf5b9
KZ
48 leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
49 rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
33141cdd
KZ
50
51 leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
52 rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
53
33141cdd 54 this.disable();
d004deee 55
e1f7a742 56 leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.LEFT_SHIFT_MODULE,
43338192
HD
57 Constants.DriveTrain.LEFT_SHIFT_FORWARD,
58 Constants.DriveTrain.LEFT_SHIFT_REVERSE);
59 rightGearPiston = new DoubleSolenoid(
60 Constants.DriveTrain.RIGHT_SHIFT_MODULE,
61 Constants.DriveTrain.RIGHT_SHIFT_FORWARD,
62 Constants.DriveTrain.RIGHT_SHIFT_REVERSE);
d9475515
HD
63
64 cheese = new CheesyDriveHelper(this);
d7bf2340
KZ
65 }
66
67 @Override
68 protected void initDefaultCommand() {
33141cdd
KZ
69 setDefaultCommand(new JoystickDrive());
70 }
71
7a4df3c5 72 // Print tne PID Output
33141cdd
KZ
73 public void printOutput() {
74 System.out.println("PIDOutput: " + pidOutput);
75 }
76
77 private double getAvgEncoderDistance() {
78 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
79 }
80
7a4df3c5
KZ
81 // Whether or not the PID Controller thinks we have reached the target
82 // setpoint
33141cdd
KZ
83 public boolean reachedTarget() {
84 if (this.onTarget()) {
85 this.disable();
86 return true;
87 } else {
88 return false;
89 }
90 }
91
92 public void stop() {
43338192 93 setMotorSpeeds(0, 0);
d7bf2340
KZ
94 }
95
96 public void resetEncoders() {
97 leftEncoder.reset();
98 rightEncoder.reset();
99 }
100
d7bf2340 101 public double getRightSpeed() {
6833a887 102 return rightEncoder.getRate(); // in inches per second
d7bf2340
KZ
103 }
104
105 public double getLeftSpeed() {
6833a887 106 return leftEncoder.getRate(); // in inches per second
d7bf2340
KZ
107 }
108
109 public double getSpeed() {
6833a887 110 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
d7bf2340
KZ
111 }
112
d7bf2340 113 public double getRightDistance() {
6833a887 114 return rightEncoder.getDistance(); // in inches
d7bf2340
KZ
115 }
116
d7bf2340 117 public double getLeftDistance() {
6833a887 118 return leftEncoder.getDistance(); // in inches
d7bf2340
KZ
119 }
120
7a4df3c5
KZ
121 // Get error between the setpoint of PID Controller and the current state of
122 // the robot
33141cdd 123 public double getError() {
f8bfcc62 124 return Math.abs(this.getSetpoint() - getAvgEncoderDistance());
33141cdd
KZ
125 }
126
127 public void printEncoder(int i, int n) {
128 if (i % n == 0) {
129 System.out.println("Left: " + this.getLeftDistance());
130 System.out.println("Right: " + this.getRightDistance());
131
132 }
133 }
134
7a4df3c5
KZ
135 /*
136 * returns the PID output that is returned by the PID Controller
137 */
33141cdd
KZ
138 public double getOutput() {
139 return pidOutput;
140 }
141
7a4df3c5 142 // Updates the PID constants based on which control mode is being used
33141cdd 143 public void updatePID() {
f8bfcc62
HD
144 this.getPIDController().setPID(Constants.DriveTrain.kp,
145 Constants.DriveTrain.ki, Constants.DriveTrain.kd);
33141cdd
KZ
146 }
147
148 public CANTalon getFrontLeft() {
149 return frontLeft;
150 }
151
152 public CANTalon getFrontRight() {
153 return frontRight;
154 }
155
156 public CANTalon getRearLeft() {
157 return rearLeft;
158 }
159
160 public CANTalon getRearRight() {
161 return rearRight;
162 }
163
7a4df3c5
KZ
164 /*
165 * Method is a required method that the PID Subsystem uses to return the
166 * calculated PID value to the driver
7236fc11 167 *
7a4df3c5
KZ
168 * @param Gives the user the output from the PID algorithm that is calculated
169 * internally
7236fc11 170 *
7a4df3c5
KZ
171 * Body: Uses the output, does some filtering and drives the robot
172 */
33141cdd
KZ
173 @Override
174 protected void usePIDOutput(double output) {
175 double left = 0;
176 double right = 0;
f8bfcc62
HD
177 double drift = this.getLeftDistance() - this.getRightDistance();
178 if (Math.abs(output) > 0 && Math.abs(output) < 0.3)
179 output = Math.signum(output) * 0.3;
180 left = output;
181 right = output + drift * Constants.DriveTrain.kp / 10;
43338192 182 setMotorSpeeds(left, right);
33141cdd 183 pidOutput = output;
d7bf2340
KZ
184 }
185
33141cdd
KZ
186 @Override
187 protected double returnPIDInput() {
188 return sensorFeedback();
d7bf2340 189 }
33141cdd 190
7a4df3c5 191 /*
c688e9da 192 * Checks the drive mode
7236fc11 193 *
7e360ef5
LM
194 * @return the current state of the robot in each state Average distance from
195 * both sides of tank drive for Encoder Mode Angle from the gyro in GYRO_MODE
7a4df3c5 196 */
33141cdd 197 private double sensorFeedback() {
f8bfcc62 198 return getAvgEncoderDistance();
33141cdd
KZ
199 }
200
43338192 201 public void joystickDrive(double left, double right) {
8d270bbc 202 // Handle flipping of the "front" of the robot
43338192 203 double k = (isFlipped() ? -1 : 1);
d9475515
HD
204 cheese.cheesyDrive(-left * k, -right,
205 getGearPistonValue() == Constants.DriveTrain.HIGH_GEAR);
33141cdd
KZ
206 }
207
208 public void setMotorSpeeds(double left, double right) {
ba29a57a 209 double k = (isFlipped() ? -1 : 1);
7236fc11
ME
210 /*
211 * cheese.cheesyDrive(-left * k, -right, getGearPistonValue() ==
212 * Constants.DriveTrain.HIGH_GEAR);
213 */
214
215 frontLeft.set(left);
216 rearLeft.set(left);
217 frontRight.set(right);
218 rearRight.set(right);
33141cdd
KZ
219 }
220
571a0e2a
HD
221 /**
222 * @return a value that is the current setpoint for the piston (kReverse or
223 * kForward)
7a4df3c5 224 */
571a0e2a
HD
225 public Value getGearPistonValue() {
226 return leftGearPiston.get(); // Pistons should always be in the same state
2a099bc6
KZ
227 }
228
571a0e2a 229 /**
7a4df3c5
KZ
230 * Changes the ball shift gear assembly to high
231 */
2a099bc6
KZ
232 public void setHighGear() {
233 changeGear(Constants.DriveTrain.HIGH_GEAR);
234 }
235
571a0e2a 236 /**
7a4df3c5
KZ
237 * Changes the ball shift gear assembly to low
238 */
2a099bc6
KZ
239 public void setLowGear() {
240 changeGear(Constants.DriveTrain.LOW_GEAR);
241 }
242
571a0e2a
HD
243 /**
244 * Changes the gear to a DoubleSolenoid.Value
7a4df3c5 245 */
2a099bc6
KZ
246 public void changeGear(DoubleSolenoid.Value gear) {
247 leftGearPiston.set(gear);
248 rightGearPiston.set(gear);
249 }
600a1a1c 250
571a0e2a
HD
251 /**
252 * Switches drivetrain gears from high to low or low to high
253 */
254 public void switchGear() {
255 Value currentValue = getGearPistonValue();
7236fc11
ME
256 Value setValue = (currentValue == Constants.DriveTrain.HIGH_GEAR)
257 ? Constants.DriveTrain.LOW_GEAR : Constants.DriveTrain.HIGH_GEAR;
571a0e2a
HD
258 changeGear(setValue);
259 }
260
261 /**
262 * Toggle whether the motor outputs are flipped, effectively switching which
263 * side of the robot is the front.
264 */
265 public void toggleFlipped() {
266 outputFlipped = !outputFlipped;
267 }
268
269 public boolean isFlipped() {
270 return outputFlipped;
271 }
272
38a404b3 273}