-
Notifications
You must be signed in to change notification settings - Fork 0
/
Limelight.java
303 lines (267 loc) · 12.1 KB
/
Limelight.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package org.team199.lib;
import org.team199.robot2020.subsystems.Drivetrain;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
public class Limelight {
public enum Mode {
DIST, STEER, TARGET
}
/* http://docs.limelightvision.io/en/latest/networktables_api.html
tv = Whether the limelight has any valid targets (0 or 1)
tx = Horizontal Offset From Crosshair To Target (-27 degrees to 27 degrees)
ty = Vertical Offset From Crosshair To Target (-20.5 degrees to 20.5 degrees)
ta = Target Area (0% of image to 100% of image)
There are more values we could be using. Check the documentation.
*/
private double tv, tx, ty, ta;
public boolean stopSteer = false;
private double mounting_angle;
private double adjustment = 0.0;
private double steering_factor = 0.25;
private double prev_tx = 1.0;
private double tolerance = 0.01;
private double backlashOffset = 0.0;
private double prevHeading = 0;
private PIDController pidController;
private boolean newPIDLoop = false;
// Parameters for vision using linear algebra.
private double[][] rotMat = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
private double[] translateVec = {0, 0, 0};
private double[] defaultValue = {0, 0, 0, 0};
public Limelight() {
SmartDashboard.putNumber("Area Threshold", 0.02);
SmartDashboard.putNumberArray("AutoAlign: PID Values", new double[]{0.015,0,0});
SmartDashboard.putNumber("AutoAlign: Tolerance", tolerance);
SmartDashboard.putNumber("AutoAlign: Backlash Offset", backlashOffset);
SmartDashboard.setPersistent("Area Threshold");
SmartDashboard.setPersistent("AutoAlign: PID Values");
SmartDashboard.setPersistent("AutoAlign: Tolerance");
SmartDashboard.setPersistent("AutoAlign: Backlash Offset");
double[] pidValues = SmartDashboard.getNumberArray("AutoAlign: PID Values", new double[]{0.02,0,0});
pidController = new PIDController(pidValues[0],pidValues[1],pidValues[2],1D/90D);
pidController.setSetpoint(0);
pidController.setTolerance(SmartDashboard.getNumber("AutoAlign: Tolerance", 0.01));
}
// For the shooter. Given what the limelight sees and the shooter angle, compute the desired initial speed for the shooter.
public double computeSpeed(double angle, double cameraHeight, double objectHeight) {
double distance = determineObjectDist(cameraHeight, objectHeight);
return Math.sqrt((16.1 * Math.pow(distance, 2)) / (distance * Math.tan(angle) - cameraHeight - objectHeight)) / Math.cos(angle);
}
/* Determine the mounting angle of the camera given a vision target and its known distance, height off of the ground,
and the height of the camera off of the ground. */
public void determineMountingAngle(double distance, double cameraHeight, double objectHeight) {
// NOTE: ty may be negative.
ty = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ty").getDouble(0.0);
mounting_angle = Math.atan((cameraHeight - objectHeight) / distance) - ty;
}
// Determine the distance an object is from the limelight given the camera's height off of the ground and the object's height off of the ground.
public double determineObjectDist(double cameraHeight, double objectHeight) {
ty = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ty").getDouble(0.0);
return (objectHeight - cameraHeight) / (Math.tan(mounting_angle + ty));
}
/* Given what is currently seen, determine the entries rotMat and translateVec parameters
by solving a system of equations using Gaussian-elimination */
public void computeParams(double[] worldXs, double[] worldYs, double[] worldZs) {
double[] cornerXs = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tcornx").getDoubleArray(defaultValue);
double[] cornerYs = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tcorny").getDoubleArray(defaultValue);
double[][] corners = {cornerXs, cornerYs, {1, 1, 1, 1}};
for (int i = 0; i < 3; i++) {
// Set up the matrix
double[][] matrix = new double[4][5];
for (int row = 0; row < 4; row++) {
matrix[row][0] = worldXs[row];
matrix[row][1] = worldYs[row];
matrix[row][2] = worldZs[row];
matrix[row][3] = 1;
matrix[row][4] = corners[i][row];
}
/* Row reduce and find solutions; assumed that echelon is of the form [I | x]
where I is the identity matrix and x are the solutions. This has not been tested yet. */
double[][] echelon = Gaussian(matrix);
rotMat[i][0] = echelon[0][4];
rotMat[i][1] = echelon[1][4];
rotMat[i][2] = echelon[2][4];
translateVec[i] = echelon[3][4];
}
}
// Adjusts the distance between a vision target and the robot. Uses basic PID with the ty value from the network table.
public double distanceAssist() {
tv = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tv").getDouble(0.0);
ta = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ta").getDouble(0.0);
SmartDashboard.putNumber("Crosshair Vertical Offset", ty);
double adjustment = 0.0;
double area_threshold = 1.75;
double Kp = 0.225;
if (tv == 1.0) {
adjustment = (area_threshold - ta) * Kp;
}
adjustment = Math.signum(adjustment) * Math.min(Math.abs(adjustment), 0.5);
return adjustment;
}
// Adjusts the angle facing a vision target. Uses basic PID with the tx value from the network table.
public double steeringAssist(Drivetrain dt) {
tv = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tv").getDouble(0.0);
tx = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tx").getDouble(0.0);
ta = NetworkTableInstance.getDefault().getTable("limelight").getEntry("ta").getDouble(0.0);
SmartDashboard.putNumber("Crosshair Horizontal Offset", tx);
SmartDashboard.putNumber("Found Vision Target", tv);
SmartDashboard.putNumber("Prev_tx", prev_tx);
tx = Double.isNaN(tx) ? 0 : tx;
double[] pidValues = SmartDashboard.getNumberArray("AutoAlign: PID Values", new double[]{0.015, 0, 0});
pidController.setPID(pidValues[0], pidValues[1], pidValues[2]);
pidController.setTolerance(SmartDashboard.getNumber("AutoAlign: Tolerance", 0.01));
if (tv == 1.0 && !stopSteer) {
if (ta > SmartDashboard.getNumber("Area Threshold", 0.02)) {
adjustment = pidController.calculate(tx);
prev_tx = tx;
if (!newPIDLoop) {
newPIDLoop = true;
pidController.setSetpoint(Math.signum(prev_tx) * SmartDashboard.getNumber("AutoAlign: Backlash Offset", backlashOffset));
}
}
} else {
newPIDLoop = false;
pidController.reset();
adjustment = Math.signum(prev_tx) * steering_factor;
}
if (Math.abs(tx) < 1.0 && Math.abs(prev_tx) < 1.0 && Math.abs(dt.getHeading() - prevHeading) < 1) stopSteer = true;
else stopSteer = false;
if(stopSteer) {
adjustment = 0;
}
prevHeading = dt.getHeading();
SmartDashboard.putBoolean("Stop Auto Steering", stopSteer);
adjustment = Math.signum(tx) * Math.min(Math.abs(adjustment), 0.5);
SmartDashboard.putNumber("Adjustment", adjustment);
return adjustment;
}
public boolean isAligned() {
return pidController.atSetpoint();
}
// Combination of distance assist and steering assist
public double[] autoTarget(Drivetrain dt) {
double dist_assist = distanceAssist();
double steer_assist = steeringAssist(dt);
double[] params = {dist_assist + steer_assist, dist_assist - steer_assist};
return params;
}
public void setLight(boolean state) {
NetworkTableInstance.getDefault().getTable("limelight").getEntry("ledMode").setNumber(state ? 3.0 : 1.0);
}
/* Given a desired straight-line distance targetDist away from the vision target, determine the distance
in order to face the target from head-on. Returns the required distance at the current heading.
*/
public double[] determineDist(double targetDist) {
// Get the x and y coordinates of the corners of the bounding box.
double[] cornerXs = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tcornx").getDoubleArray(defaultValue);
double[] cornerYs = NetworkTableInstance.getDefault().getTable("limelight").getEntry("tcorny").getDoubleArray(defaultValue);
// Average the corners to get the center of the vision target as viewed by the camera.
double xSum = 0.0;
double ySum = 0.0;
for (int i = 0; i < 4; i += 1) {
xSum += cornerXs[i];
ySum += cornerYs[i];
}
double[] cameraPos = {xSum / 4, ySum / 4, 1};
// Calculate the position of the center in 3D space.
double[] worldPos = dot(transpose(rotMat), difference(cameraPos, translateVec));
double x = worldPos[0];
double y = worldPos[1];
// Use trigonometry to find the required distance.
double r = Math.sqrt(x * x + y * y);
double a1 = Math.atan2(y, x);
double a3 = Math.asin(r * Math.sin(a1) / targetDist);
double a2 = Math.PI - a1 - a3;
double[] params = {r * Math.sin(a2) / Math.sin(a3), a3};
return params;
}
// Returns the transpose of a matrix.
private double[][] transpose(double[][] matrix) {
int n = matrix.length;
int m = matrix[0].length;
double[][] matrixTranspose = new double[m][n];
for (int i = 0; i < n; i++) {
for (int j = 0; j < m; j++) {
matrixTranspose[m][n] = matrix[n][m];
}
}
return matrixTranspose;
}
// Returns matrix-vector product.
private double[] dot(double[][] matrix, double[] vector) {
int n = matrix.length;
int m = matrix[0].length;
assert m == vector.length;
double[] dotVector = new double[n];
for (int i = 0; i < n; i++) {
dotVector[i] = dot(matrix[i], vector);
}
return dotVector;
}
// Returns x * yT.
private double dot(double[] x, double[] y) {
int n = x.length;
assert x.length == y.length;
double dot = 0.0;
for (int i = 0; i < n; i++) { dot += x[i] * y[i]; }
return dot;
}
// Returns the difference of two vectors.
private double[] difference(double[] x, double[] y) {
double[] diff = new double[x.length];
for (int i = 0; i < x.length; i++) { diff[i] = x[i] - y[i]; }
return diff;
}
// Returns the reduced row-echelon form of a matrix.
private double[][] Gaussian(double[][] matrix) {
int n = matrix.length;
int m = matrix[0].length;
double[][] echelon = new double[n][];
for(int i = 0; i < matrix.length; i++) {
echelon[i] = matrix[i].clone();
}
while (!isEchelon(echelon)) {
for (int i = 0; i < Math.min(n, m); i++) {
double pivot = matrix[i][i];
if (pivot != 0) {
if (pivot != 1) {
for (int j = 0; j < m; j++) { echelon[i][j] /= pivot; }
}
for (int rowNum = 0; rowNum < n; rowNum++) {
for (int j = 0; j < m; j++) { echelon[rowNum][j] -= echelon[rowNum][i] * echelon[i][j]; }
}
}
}
}
return echelon;
}
// Tests whether a matrix is in reduced-row-echelon form
private boolean isEchelon(double[][] matrix) {
int n = matrix.length;
int m = matrix[0].length;
double[][] matrixTranspose = transpose(matrix);
for (int i = 0; i < n; i++) {
for (int j = 0; j < m; j++) {
double val = matrix[i][j];
if (Math.abs(val) > 0) {
int non_zero_count = 0;
for (int k = 0; k < n; k++) {
if (matrixTranspose[j][k] != 0) { non_zero_count += 1; }
}
if (non_zero_count != 1){ return false; }
}
}
}
return true;
}
public PIDController getPIDController() {
return pidController;
}
}