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