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.GyroLib; |
5 | import org.usfirst.frc.team3501.robot.MathLib; | |
6 | import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; | |
111dc444 | 7 | |
38a404b3 | 8 | import edu.wpi.first.wpilibj.CANTalon; |
111dc444 YN |
9 | import edu.wpi.first.wpilibj.CounterBase.EncodingType; |
10 | import edu.wpi.first.wpilibj.Encoder; | |
b54ad73b | 11 | import edu.wpi.first.wpilibj.I2C; |
33141cdd KZ |
12 | import edu.wpi.first.wpilibj.RobotDrive; |
13 | import edu.wpi.first.wpilibj.command.PIDSubsystem; | |
14 | ||
15 | public class DriveTrain extends PIDSubsystem { | |
16 | private static double pidOutput = 0; | |
17 | private static double encoderTolerance = 8.0, gyroTolerance = 5.0; | |
18 | private int DRIVE_MODE = 1; | |
19 | ||
20 | private static final int MANUAL_MODE = 1, ENCODER_MODE = 2, GYRO_MODE = 3; | |
38a404b3 | 21 | |
1884c3cf | 22 | private Encoder leftEncoder, rightEncoder; |
d7bf2340 | 23 | private CANTalon frontLeft, frontRight, rearLeft, rearRight; |
33141cdd KZ |
24 | private RobotDrive robotDrive; |
25 | ||
26 | private GyroLib gyro; | |
71d73690 | 27 | |
d7bf2340 | 28 | public DriveTrain() { |
33141cdd KZ |
29 | super(kp, ki, kd); |
30 | ||
d7bf2340 KZ |
31 | frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); |
32 | frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); | |
33 | rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); | |
34 | rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); | |
1884c3cf | 35 | |
33141cdd | 36 | robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); |
d7bf2340 KZ |
37 | leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, |
38 | Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X); | |
39 | rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, | |
40 | Constants.DriveTrain.ENCODER_RIGHT_B, false, EncodingType.k4X); | |
45bdf5b9 KZ |
41 | leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); |
42 | rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); | |
33141cdd KZ |
43 | |
44 | leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); | |
45 | rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE); | |
46 | ||
47 | gyro = new GyroLib(I2C.Port.kOnboard, false); | |
48 | ||
49 | DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE; | |
50 | setEncoderPID(); | |
51 | this.disable(); | |
52 | gyro.start(); | |
d004deee | 53 | |
d7bf2340 KZ |
54 | } |
55 | ||
56 | @Override | |
57 | protected void initDefaultCommand() { | |
33141cdd KZ |
58 | setDefaultCommand(new JoystickDrive()); |
59 | } | |
60 | ||
61 | public void printOutput() { | |
62 | System.out.println("PIDOutput: " + pidOutput); | |
63 | } | |
64 | ||
65 | private double getAvgEncoderDistance() { | |
66 | return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; | |
67 | } | |
68 | ||
69 | public boolean reachedTarget() { | |
70 | if (this.onTarget()) { | |
71 | this.disable(); | |
72 | return true; | |
73 | } else { | |
74 | return false; | |
75 | } | |
76 | } | |
77 | ||
78 | public void stop() { | |
79 | drive(0, 0); | |
d7bf2340 KZ |
80 | } |
81 | ||
82 | public void resetEncoders() { | |
83 | leftEncoder.reset(); | |
84 | rightEncoder.reset(); | |
85 | } | |
86 | ||
d7bf2340 | 87 | public double getRightSpeed() { |
6833a887 | 88 | return rightEncoder.getRate(); // in inches per second |
d7bf2340 KZ |
89 | } |
90 | ||
91 | public double getLeftSpeed() { | |
6833a887 | 92 | return leftEncoder.getRate(); // in inches per second |
d7bf2340 KZ |
93 | } |
94 | ||
95 | public double getSpeed() { | |
6833a887 | 96 | return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second |
d7bf2340 KZ |
97 | } |
98 | ||
d7bf2340 | 99 | public double getRightDistance() { |
6833a887 | 100 | return rightEncoder.getDistance(); // in inches |
d7bf2340 KZ |
101 | } |
102 | ||
d7bf2340 | 103 | public double getLeftDistance() { |
6833a887 | 104 | return leftEncoder.getDistance(); // in inches |
d7bf2340 KZ |
105 | } |
106 | ||
33141cdd KZ |
107 | public double getError() { |
108 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) | |
109 | return Math.abs(this.getSetpoint() - getAvgEncoderDistance()); | |
110 | else | |
111 | return Math.abs(this.getSetpoint() + getGyroAngle()); | |
d7bf2340 KZ |
112 | } |
113 | ||
33141cdd KZ |
114 | public double getGyroAngle() { |
115 | return gyro.getRotationZ().getAngle(); | |
116 | } | |
117 | ||
118 | public void resetGyro() { | |
119 | gyro.reset(); | |
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 | ||
130 | public void printGyroOutput() { | |
131 | System.out.println("Gyro Angle" + -this.getGyroAngle()); | |
132 | } | |
133 | ||
134 | public double getOutput() { | |
135 | return pidOutput; | |
136 | } | |
137 | ||
138 | public void updatePID() { | |
139 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) | |
140 | this.getPIDController().setPID(kp, ki, kd); | |
141 | else | |
142 | this.getPIDController().setPID(gp, gd, gi); | |
143 | } | |
144 | ||
145 | public CANTalon getFrontLeft() { | |
146 | return frontLeft; | |
147 | } | |
148 | ||
149 | public CANTalon getFrontRight() { | |
150 | return frontRight; | |
151 | } | |
152 | ||
153 | public CANTalon getRearLeft() { | |
154 | return rearLeft; | |
155 | } | |
156 | ||
157 | public CANTalon getRearRight() { | |
158 | return rearRight; | |
159 | } | |
160 | ||
161 | public int getMode() { | |
162 | return DRIVE_MODE; | |
163 | } | |
164 | ||
165 | @Override | |
166 | protected void usePIDOutput(double output) { | |
167 | double left = 0; | |
168 | double right = 0; | |
169 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) { | |
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 * kp / 10; | |
175 | } | |
176 | else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) { | |
177 | left = output; | |
178 | right = -output; | |
179 | } | |
180 | drive(left, right); | |
181 | pidOutput = output; | |
d7bf2340 KZ |
182 | } |
183 | ||
33141cdd KZ |
184 | @Override |
185 | protected double returnPIDInput() { | |
186 | return sensorFeedback(); | |
d7bf2340 | 187 | } |
33141cdd KZ |
188 | |
189 | private double sensorFeedback() { | |
190 | if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) | |
191 | return getAvgEncoderDistance(); | |
192 | else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) | |
193 | return -this.getGyroAngle(); | |
194 | // counterclockwise is positive on joystick but we want it to be negative | |
195 | else | |
196 | return 0; | |
197 | } | |
198 | ||
199 | public void drive(double left, double right) { | |
200 | robotDrive.tankDrive(-left, -right); | |
201 | // dunno why but inverted drive (- values is forward) | |
202 | } | |
203 | ||
204 | public void driveDistance(double dist, double maxTimeOut) { | |
205 | dist = MathLib.constrain(dist, -100, 100); | |
206 | setEncoderPID(); | |
207 | setSetpoint(dist); | |
208 | } | |
209 | ||
210 | public void setEncoderPID() { | |
211 | DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE; | |
212 | this.updatePID(); | |
213 | this.setAbsoluteTolerance(encoderTolerance); | |
214 | this.setOutputRange(-1.0, 1.0); | |
215 | this.setInputRange(-200.0, 200.0); | |
216 | this.enable(); | |
217 | } | |
218 | ||
219 | private void setGyroPID() { | |
220 | DRIVE_MODE = Constants.DriveTrain.GYRO_MODE; | |
221 | this.updatePID(); | |
222 | this.getPIDController().setPID(gp, gi, gd); | |
223 | ||
224 | this.setAbsoluteTolerance(gyroTolerance); | |
225 | this.setOutputRange(-1.0, 1.0); | |
226 | this.setInputRange(-360.0, 360.0); | |
227 | this.enable(); | |
228 | } | |
229 | ||
230 | public void turnAngle(double angle) { | |
231 | angle = MathLib.constrain(angle, -360, 360); | |
232 | setGyroPID(); | |
233 | setSetpoint(angle); | |
234 | } | |
235 | ||
236 | public void setMotorSpeeds(double left, double right) { | |
237 | // positive setpoint to left side makes it go backwards | |
238 | // positive setpoint to right side makes it go forwards. | |
239 | frontLeft.set(-left); | |
240 | rearLeft.set(-left); | |
241 | frontRight.set(right); | |
242 | rearRight.set(right); | |
243 | } | |
244 | ||
245 | private static double kp = 0.013, ki = 0.000015, kd = -0.002; | |
246 | private static double gp = 0.018, gi = 0.000015, gd = 0; | |
38a404b3 | 247 | } |