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