Skip to content

Commit 1e3257d

Browse files
updates
1 parent 0cd9218 commit 1e3257d

File tree

2 files changed

+21
-22
lines changed

2 files changed

+21
-22
lines changed

.vscode/spellright.dict

+1
Original file line numberDiff line numberDiff line change
@@ -141,3 +141,4 @@ fn
141141
eToSratio
142142
Ncoder
143143
Dpad
144+
Limelights

src/main/java/frc/robot/vision/Vision.java

+20-22
Original file line numberDiff line numberDiff line change
@@ -22,23 +22,21 @@ public class Vision extends SubsystemBase {
2222

2323
public static final class VisionConfig {
2424
/* Limelight Configuration */
25-
public static final String LEFT_LL = "limelight-left";
25+
public static final String FRONT_LL = "limelight-front";
2626
public static final LimelightConfig LEFT_Config =
27-
new LimelightConfig(LEFT_LL)
28-
.withTranslation(0, 0, 0.5)
29-
.withRotation(0, Math.toRadians(-15), 0);
27+
new LimelightConfig(FRONT_LL)
28+
.withTranslation(0.215, 0, 0.188)
29+
.withRotation(0, Math.toRadians(28), 0);
3030

31-
public static final String RIGHT_LL = "limelight-right";
31+
public static final String BACK_LL = "limelight-back";
3232
public static final LimelightConfig Right_Config =
33-
new LimelightConfig(RIGHT_LL)
34-
.withTranslation(0, 0.5, 0.5)
35-
.withRotation(0, Math.toRadians(15), 0);
36-
37-
// TODO: Limelight config needs to be updated to actual position on robot
33+
new LimelightConfig(BACK_LL)
34+
.withTranslation(-0.215, 0.0, 0.188)
35+
.withRotation(0, Math.toRadians(28), Math.toRadians(180));
3836

3937
/* Pipeline configs */
40-
public static final int leftTagPipeline = 0;
41-
public static final int rightTagPipeline = 1;
38+
public static final int frontTagPipeline = 0;
39+
public static final int backTagPipeline = 0;
4240

4341
/* Pose Estimation Constants */
4442

@@ -59,19 +57,19 @@ public static final class VisionConfig {
5957
}
6058

6159
/** Limelights */
62-
public final Limelight leftLL =
60+
public final Limelight frontLL =
6361
new Limelight(
64-
VisionConfig.LEFT_LL, VisionConfig.leftTagPipeline, VisionConfig.LEFT_Config);
62+
VisionConfig.FRONT_LL, VisionConfig.frontTagPipeline, VisionConfig.LEFT_Config);
6563

66-
public final LimelightLogger leftLLogger = new LimelightLogger("left", leftLL);
64+
public final LimelightLogger leftLLogger = new LimelightLogger("left", frontLL);
6765

68-
public final Limelight rightLL =
66+
public final Limelight backLL =
6967
new Limelight(
70-
VisionConfig.RIGHT_LL,
71-
VisionConfig.rightTagPipeline,
68+
VisionConfig.BACK_LL,
69+
VisionConfig.backTagPipeline,
7270
VisionConfig.Right_Config);
7371

74-
public final Limelight[] allLimelights = {leftLL, rightLL};
72+
public final Limelight[] allLimelights = {frontLL, backLL};
7573

7674
private final DecimalFormat df = new DecimalFormat();
7775

@@ -108,7 +106,7 @@ public void resetPoseToVision() {
108106
}
109107

110108
public Limelight getBestLimelight() {
111-
Limelight bestLimelight = leftLL;
109+
Limelight bestLimelight = frontLL;
112110
double bestScore = 0;
113111
for (Limelight limelight : allLimelights) {
114112
double score = 0;
@@ -239,10 +237,10 @@ public Command blinkLimelights() {
239237
public Command solidLimelight() {
240238
return startEnd(
241239
() -> {
242-
leftLL.setLEDMode(true);
240+
frontLL.setLEDMode(true);
243241
},
244242
() -> {
245-
leftLL.setLEDMode(false);
243+
frontLL.setLEDMode(false);
246244
})
247245
.withName("Vision.solidLimelight");
248246
}

0 commit comments

Comments
 (0)