Skip to content

Commit 82f2c96

Browse files
authored
converted to using estimationmode instead of boolean for estimation mode (mt1 , mt2) (#12)
1 parent 627ae60 commit 82f2c96

File tree

5 files changed

+137
-119
lines changed

5 files changed

+137
-119
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ limelight.getSettings()
7272
.save();
7373

7474
// Get MegaTag2 pose
75-
Optional<PoseEstimate> visionEstimate = limelight.createPoseEstimator(true).getPoseEstimate();
75+
Optional<PoseEstimate> visionEstimate = limelight.createPoseEstimator(EstimationMode.MEGATAG2).getPoseEstimate();
7676
// If the pose is present
7777
visionEstimate.ifPresent((PoseEstimate poseEstimate) -> {
7878
// Add it to the pose estimator.

example/src/main/java/frc/robot/subsystems/DrivebaseSubsystem.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
import limelight.networktables.LimelightSettings.LEDMode;
3333
import limelight.networktables.Orientation3d;
3434
import limelight.networktables.PoseEstimate;
35+
import limelight.networktables.LimelightPoseEstimator.EstimationMode;
3536
import limelight.networktables.target.pipeline.NeuralClassifier;
3637

3738
public class DrivebaseSubsystem extends SubsystemBase
@@ -86,7 +87,7 @@ public DrivebaseSubsystem()
8687
.withLimelightLEDMode(LEDMode.PipelineControl)
8788
.withCameraOffset(cameraOffset)
8889
.save();
89-
poseEstimator = limelight.createPoseEstimator(true);
90+
poseEstimator = limelight.createPoseEstimator(EstimationMode.MEGATAG2);
9091

9192
}
9293

yall/java/limelight/Limelight.java

Lines changed: 56 additions & 63 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
package limelight;
22

3-
43
import static edu.wpi.first.units.Units.Milliseconds;
54
import static edu.wpi.first.units.Units.Seconds;
65
import static limelight.networktables.LimelightUtils.getLimelightURLString;
@@ -20,36 +19,35 @@
2019
import limelight.networktables.LimelightPoseEstimator;
2120
import limelight.networktables.LimelightResults;
2221
import limelight.networktables.LimelightSettings;
22+
import limelight.networktables.LimelightPoseEstimator.EstimationMode;
2323

2424
/**
2525
* Limelight Camera class.
2626
*/
27-
public class Limelight
28-
{
27+
public class Limelight {
2928

3029
/**
3130
* {@link Limelight} name.
3231
*/
33-
public final String limelightName;
32+
public final String limelightName;
3433
/**
3534
* {@link Limelight} data from NetworkTables.
3635
*/
37-
private LimelightData limelightData;
36+
private LimelightData limelightData;
3837
/**
3938
* {@link Limelight} settings that we apply.
4039
*/
41-
private LimelightSettings settings;
40+
private LimelightSettings settings;
4241

42+
static final long ONE_SECOND_IN_MILI = (long) Seconds.of(1).in(Milliseconds);
4343

4444
/**
4545
* Constructs and configures the {@link Limelight} NT Values.
4646
*
4747
* @param name Name of the limelight
4848
*/
49-
public Limelight(String name)
50-
{
51-
if (!isAvailable(name) && !RobotBase.isSimulation())
52-
{
49+
public Limelight(String name) {
50+
if (!isAvailable(name) && !RobotBase.isSimulation()) {
5351
throw new RuntimeException("Limelight not available");
5452
}
5553

@@ -61,71 +59,75 @@ public Limelight(String name)
6159
/**
6260
* Verify limelight name exists as a table in NT.
6361
* <p>
64-
* This check is expected to be run once during robot construction and is not intended to be checked in the iterative
62+
* This check is expected to be run once during robot construction and is not
63+
* intended to be checked in the iterative
6564
* loop.
6665
* <p>
67-
* Use check "yourLimelightObject.getData().targetData.getTargetStatus())"" for the validity of an iteration for 2d
66+
* Use check "yourLimelightObject.getData().targetData.getTargetStatus())"" for
67+
* the validity of an iteration for 2d
6868
* targeting.
6969
* <p>
70-
* For valid 3d pose check "yourLimelightPoseEstimatorObject.getPoseEstimate().get().hasData"
70+
* For valid 3d pose check
71+
* "yourLimelightPoseEstimatorObject.getPoseEstimate().get().hasData"
7172
*
7273
* @param limelightName Limelight Name to check for table existence.
7374
* @return true if an NT table exists with requested LL name.
74-
* <p>false and issues a WPILib Error Alert if requested LL doesn't appear as an NT table.
75+
* <p>
76+
* false and issues a WPILib Error Alert if requested LL doesn't appear
77+
* as an NT table.
7578
*/
7679
@SuppressWarnings("resource")
77-
public static boolean isAvailable(String limelightName)
78-
{
80+
public static boolean isAvailable(String limelightName) {
7981
// LL sends key "getpipe" if it's on so check that
80-
// put in a delay if needed to help assure NT has latched onto the LL if it is transmitting
81-
for (int i = 1; i <= 15; i++)
82-
{
83-
if (NetworkTableInstance.getDefault().getTable(limelightName).containsKey("getpipe"))
84-
{
82+
// put in a delay if needed to help assure NT has latched onto the LL if it is
83+
// transmitting
84+
for (int i = 1; i <= 15; i++) {
85+
if (NetworkTableInstance.getDefault().getTable(limelightName).containsKey("getpipe")) {
8586
return true;
8687
}
87-
//System.out.println("waiting " + i + " of 15 seconds for limelight to attach");
88-
try
89-
{
90-
Thread.sleep((long) Seconds.of(1).in(Milliseconds));
91-
} catch (InterruptedException e)
92-
{
88+
// System.out.println("waiting " + i + " of 15 seconds for limelight to
89+
// attach");
90+
try {
91+
Thread.sleep(ONE_SECOND_IN_MILI);
92+
} catch (InterruptedException e) {
9393
e.printStackTrace();
9494
}
9595
}
9696
String errMsg = "Your limelight name \"" + limelightName +
97-
"\" is invalid. doesn't exist on the network (no getpipe key).\n" +
98-
"These may be available:" +
99-
NetworkTableInstance.getDefault().getTable("/").getSubTables().stream()
100-
.filter(ntName -> ((String) (ntName)).startsWith("limelight"))
101-
.collect(Collectors.joining("\n"));
97+
"\" is invalid. doesn't exist on the network (no getpipe key).\n" +
98+
"These may be available:" +
99+
NetworkTableInstance.getDefault().getTable("/").getSubTables().stream()
100+
.filter(ntName -> ((String) (ntName)).startsWith("limelight"))
101+
.collect(Collectors.joining("\n"));
102102
new Alert(errMsg, AlertType.kError).set(true);
103103
return false;
104104
}
105105

106106
/**
107107
* Create a {@link LimelightPoseEstimator} for the {@link Limelight}.
108108
*
109-
* @param megatag2 Use MegaTag2.
109+
* @param estimationMode Estimation mode to use (MEGATAG1 / MEGATAG2).
110110
* @return {@link LimelightPoseEstimator}
111111
*/
112-
public LimelightPoseEstimator createPoseEstimator(boolean megatag2)
113-
{
114-
return new LimelightPoseEstimator(this, megatag2);
112+
public LimelightPoseEstimator createPoseEstimator(EstimationMode estimationMode) {
113+
return new LimelightPoseEstimator(this, estimationMode);
115114
}
116115

117116
/**
118117
* Get the {@link LimelightSettings} preparatory to changing settings.
119-
* <p>While this method does get current settings from the LL there are
120-
* no getters provided for the settings so they are useless, dead data. This merely provides a stub for the various
118+
* <p>
119+
* While this method does get current settings from the LL there are
120+
* no getters provided for the settings so they are useless, dead data. This
121+
* merely provides a stub for the various
121122
* ".withXXXX" settings to attach to.
122-
* <p>This method may be used as often as needed and may contain none or more
123+
* <p>
124+
* This method may be used as often as needed and may contain none or more
123125
* chained ".withXXXX" settings.
124126
*
125-
* @return object used as the target of the various ".withXXXX" settings methods.
127+
* @return object used as the target of the various ".withXXXX" settings
128+
* methods.
126129
*/
127-
public LimelightSettings getSettings()
128-
{
130+
public LimelightSettings getSettings() {
129131
return settings;
130132
}
131133

@@ -134,8 +136,7 @@ public LimelightSettings getSettings()
134136
*
135137
* @return {@link LimelightData} object.
136138
*/
137-
public LimelightData getData()
138-
{
139+
public LimelightData getData() {
139140
return limelightData;
140141
}
141142

@@ -144,50 +145,43 @@ public LimelightData getData()
144145
*
145146
* @param snapshotname Snapshot name to save.
146147
*/
147-
public void snapshot(String snapshotname)
148-
{
148+
public void snapshot(String snapshotname) {
149149
CompletableFuture.supplyAsync(() -> {
150150
URL url = getLimelightURLString(limelightName, "capturesnapshot");
151-
try
152-
{
151+
try {
153152
HttpURLConnection connection = (HttpURLConnection) url.openConnection();
154153
connection.setRequestMethod("GET");
155-
if (snapshotname != null && snapshotname != "")
156-
{
154+
if (snapshotname != null && snapshotname != "") {
157155
connection.setRequestProperty("snapname", snapshotname);
158156
}
159157

160158
int responseCode = connection.getResponseCode();
161-
if (responseCode == 200)
162-
{
159+
if (responseCode == 200) {
163160
return true;
164-
} else
165-
{
161+
} else {
166162
System.err.println("Bad LL Request");
167163
}
168-
} catch (IOException e)
169-
{
164+
} catch (IOException e) {
170165
System.err.println(e.getMessage());
171166
}
172167
return false;
173168
});
174169
}
175170

176171
/**
177-
* Gets the latest JSON {@link LimelightResults} output and returns a LimelightResults object.
172+
* Gets the latest JSON {@link LimelightResults} output and returns a
173+
* LimelightResults object.
178174
*
179175
* @return LimelightResults object containing all current target data
180176
*/
181-
public Optional<LimelightResults> getLatestResults()
182-
{
177+
public Optional<LimelightResults> getLatestResults() {
183178
return limelightData.getResults();
184179
}
185180

186181
/**
187182
* Flush the NetworkTable data to server.
188183
*/
189-
public void flush()
190-
{
184+
public void flush() {
191185
NetworkTableInstance.getDefault().flush();
192186
}
193187

@@ -196,8 +190,7 @@ public void flush()
196190
*
197191
* @return {@link NetworkTable} for this limelight.
198192
*/
199-
public NetworkTable getNTTable()
200-
{
193+
public NetworkTable getNTTable() {
201194
return NetworkTableInstance.getDefault().getTable(limelightName);
202195
}
203196
}

0 commit comments

Comments
 (0)