Skip to content

Commit

Permalink
I hate NetworkTables Unit Testing :(
Browse files Browse the repository at this point in the history
  • Loading branch information
cuttestkittensrule committed Feb 21, 2024
1 parent 08a0f48 commit 3db9b65
Show file tree
Hide file tree
Showing 9 changed files with 373 additions and 6 deletions.
3 changes: 0 additions & 3 deletions .gitmodules
Original file line number Diff line number Diff line change
@@ -1,3 +0,0 @@
[submodule "limelight/src/main/java/frc/robot"]
path = limelight/src/main/java/frc/robot
url = https://github.com/LimelightVision/limelightlib-wpijava
2 changes: 0 additions & 2 deletions lib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,6 @@ repositories {
}

dependencies {
implementation project(':limelight')

implementation wpi.java.deps.wpilib()
implementation wpi.java.vendor.java()

Expand Down
Binary file modified lib/ctre_sim/Talon FX vers. C - 00 - 0 - ext.dat
Binary file not shown.
2 changes: 2 additions & 0 deletions limelight/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@ repositories {

dependencies {
implementation wpi.java.deps.wpilib()
api "org.json:json:20240205"

testImplementation 'junit:junit:4.13.2'
}

Expand Down
117 changes: 117 additions & 0 deletions limelight/src/main/java/com/team2813/lib2813/limelight/Limelight.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,117 @@
package com.team2813.lib2813.limelight;

import java.util.HashMap;
import java.util.Map;
import java.util.Objects;
import java.util.Optional;
import java.util.OptionalLong;

import org.json.JSONObject;

import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;

public class Limelight {
private static Map<String, Limelight> limelights = new HashMap<>();
private static NetworkTableInstance tableInstance = null;
private final NetworkTable limelightTable;
private final LimelightConfig limelightConfig;

// specific types of data;
private final LocationalData data;

private Limelight(String name) {
if (tableInstance == null) {
tableInstance = NetworkTableInstance.getDefault();
}
limelightTable = tableInstance.getTable(name);
data = new LocationalData(this);
limelightConfig = new LimelightConfig(this);
}

NetworkTable networkTable() {
return limelightTable;
}

public Optional<JSONObject> getJsonDump() {
String json = limelightTable.getEntry("json").getString(null);
return json == null ? Optional.empty() : Optional.of(
new JSONObject(json)
);
}

public OptionalLong getPipeline() {
long pipeline = limelightTable.getEntry("pipeline").getInteger(-1);
return pipeline == -1 ? OptionalLong.empty() : OptionalLong.of(pipeline);
}

/**
* Sets the pipeline
* @param val the pipeline number [0, 9]
* @throws IllegalArgumentException if the pipeline is invalid
*/
public void setPipeline(int val) {
if (val > 9 || val < 0) {
throw new IllegalArgumentException("Invalid pipeline number");
}
limelightTable.getEntry("pipeline").setInteger(val);
}

/**
* Gets an object for getting locational data
* @return an object for getting locational data
*/
public LocationalData getLocationalData() {
return data;
}

/**
* Gets an object for configuring the limelight
* @return an object for configuring the limelight
*/
public LimelightConfig getConfig() {
return limelightConfig;
}

/**
* Checks if the limelight has a target
* @return {@code true} if there is a target seen by the limelight
*/
public boolean hasTarget() {
return 1 == limelightTable.getEntry("tv").getInteger(0);
}

/**
* Gets the limelight with the default name.
* @return the {@link Limelight} object for interfacing with the limelight
*/
public static Limelight getDefaultLimelight() {
return getLimelight("");
}

/**
* Gets the limelight with the specified name. Calling with a blank {@code limelightName}
* is equivilent to calling {@link #getDefaultLimelight()}
* @param limelightName The name of the limelight to interface with
* @return the {@link Limelight} object for interfacing with the limelight
* @throws NullPointerException if {@code limelightName} is null
*/
public static Limelight getLimelight(String limelightName) {
String table = Objects.requireNonNull("limelightName shouldn't be null", limelightName)
.isBlank() ? "limelight" : limelightName;
return limelights.computeIfAbsent(table, Limelight::new);
}

static void eraseInstances() {
limelights.clear();
}

/**
* Sets the {@link NetworkTableInstance} to use for creating new {@link Limelight} objects.
* For testing purposes; call <strong>before</strong> getting a limelight instance
* @param tableInstance
*/
static void setTableInstance(NetworkTableInstance tableInstance) {
Limelight.tableInstance = tableInstance;
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
package com.team2813.lib2813.limelight;

import java.util.stream.Stream;
import static java.util.stream.Collectors.*;

import java.util.Map;
import java.util.Objects;
import java.util.Optional;

import edu.wpi.first.networktables.NetworkTable;

public class LimelightConfig {
private final NetworkTable table;
LimelightConfig(Limelight limelight) {
table = Objects.requireNonNull(limelight).networkTable();
}

public Optional<LedMode> getLedMode() {
return LedMode.fromId(table.getEntry("ledMode").getInteger(-1));
}

public void setLedMode(LedMode mode) {
table.getEntry("ledMode").setInteger(mode.getID());
}

public Optional<CamMode> getCamMode() {
return CamMode.fromId(table.getEntry("camMode").getInteger(-1));
}

public void setCamMode(CamMode mode) {
table.getEntry("camMode").setInteger(mode.getID());
}

public Optional<Snapshot> getSnapshot() {
return Snapshot.fromId(table.getEntry("snapshot").getInteger(-1));
}

public void setSnapshot(Snapshot snapshot) {
table.getEntry("snapshot").setInteger(snapshot.getID());
}

public Optional<StreamMode> getStreamMode() {
return StreamMode.fromId(table.getEntry("stream").getInteger(-1));
}

public void setStreamMode(StreamMode mode) {
table.getEntry("stream").setInteger(mode.getID());
}

/**
* Sets the crop rectangle for the limelight
* @param crop the array describing the crop
*/
public void setCrop(double[] crop) {
table.getEntry("crop").setDoubleArray(crop);
}

public static enum LedMode {
/** default pipeline value */
DEFAULT(0),
/** force to off */
OFF(1),
/** force to blink */
BLINK(2),
/** force to on */
ON(3);
private final long id;
private static Map<Long, LedMode> map =
Stream.of(values()).collect(toMap(LedMode::getID,(k) -> k, (o, n) -> n));
LedMode(long id) {
this.id = id;
}
private long getID() {
return id;
}
private static Optional<LedMode> fromId(long id) {
return Optional.ofNullable(map.get(id));
}
}

public static enum CamMode {
VISION(0),
DRIVER_CAMERA(1);
private final long id;
private static Map<Long, CamMode> map =
Stream.of(values()).collect(toMap(CamMode::getID,(k) -> k, (o, n) -> n));
CamMode(long id) {
this.id = id;
}
private long getID() {
return id;
}
private static Optional<CamMode> fromId(long id) {
return Optional.ofNullable(map.get(id));
}
}

public static enum Snapshot {
RESET(0),
TAKE_ONE(1);
private final long id;
private static Map<Long, Snapshot> map =
Stream.of(values()).collect(toMap(Snapshot::getID,(k) -> k, (o, n) -> n));
Snapshot(long id) {
this.id = id;
}
private long getID() {
return id;
}
private static Optional<Snapshot> fromId(long id) {
return Optional.ofNullable(map.get(id));
}
}

public static enum StreamMode {
STANDARD(0),
MAIN(1),
SECONDARY(2);
private final long id;
private static Map<Long, StreamMode> map =
Stream.of(values()).collect(toMap(StreamMode::getID, (k) -> k, (o, n) -> n));
StreamMode(long id) {
this.id = id;
}
private long getID() {
return id;
}
private static Optional<StreamMode> fromId(long id) {
return Optional.ofNullable(map.get(id));
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
package com.team2813.lib2813.limelight;

import java.util.Optional;
import java.util.OptionalLong;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.networktables.NetworkTable;

/**
* Get positional data from limelight
* @see Limelight
*/
public class LocationalData {
private final NetworkTable table;
private final Limelight limelight;
private static final double[] defaultArr = new double[0];

LocationalData(Limelight limelight) {
this.limelight = limelight;
this.table = limelight.networkTable();
}

private Optional<Pose3d> parseArr(double[] arr) {
if (arr == defaultArr || arr.length < 6) {
return Optional.empty();
}
Rotation3d rotation = new Rotation3d(arr[3], arr[4], arr[5]);
return Optional.of(new Pose3d(arr[0], arr[1], arr[2], rotation));
}

/**
* Gets the position of the robot with the center of the field as the origin
* @return The position of the robot
*/
public Optional<Pose3d> getBotpose() {
return parseArr(table.getEntry("botpose").getDoubleArray(defaultArr));
}

/**
* Gets the position of the robot with the blue driverstation as the origin
* @return The position of the robot
*/
public Optional<Pose3d> getBotposeBlue() {
return parseArr(table.getEntry("botpose_wpiblue").getDoubleArray(defaultArr));
}

/**
* Gets the position of the robot with the red driverstation as the origin
* @return The position of the robot
*/
public Optional<Pose3d> getBotposeRed() {
return parseArr(table.getEntry("botpose_wpired").getDoubleArray(defaultArr));
}

/**
* Gets the id of the targeted tag.
*/
public OptionalLong getTagID() {
long tid = table.getEntry("tid").getInteger(0);
return limelight.hasTarget() ? OptionalLong.of(tid) : OptionalLong.empty();
}
}
1 change: 0 additions & 1 deletion limelight/src/main/java/frc/robot
Submodule robot deleted from c36a80
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
package com.team2813.lib2813.limelight;

import static org.junit.Assert.assertEquals;
import static org.junit.Assert.assertFalse;
import static org.junit.Assert.assertTrue;

import org.junit.After;
import org.junit.Before;
import org.junit.Test;

import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;

public class LimelightTest {
NetworkTableInstance instance;
@Before
public void setup() {
instance = NetworkTableInstance.create();
instance.startLocal();
Limelight.setTableInstance(instance);
instance.flushLocal();
}

@After
public void cleanup() {
instance.close();
Limelight.eraseInstances();
}

@Test
public void equality() {
Limelight a = Limelight.getDefaultLimelight();
Limelight b = Limelight.getDefaultLimelight();
assertEquals("Default limelight call returned different values", a, b);
Limelight c = Limelight.getLimelight("limelight");
assertEquals(
"Default limelights not equal to limelights named \"limelight\" (default)",
a, c
);
}

@Test
public void emptyValues() {
Limelight limelight = Limelight.getDefaultLimelight();
assertFalse("NetworkTables should be empty", limelight.getPipeline().isPresent());
}

@Test
public void changingTables() {
Limelight limelight = Limelight.getDefaultLimelight();
NetworkTable table = instance.getTable("limelight");
table.getEntry("tv").setInteger(0);
instance.flushLocal();
assertFalse("Value of 0 not false", limelight.hasTarget());
table.getEntry("tv").setInteger(1);
instance.flushLocal();
assertTrue("Value of 1 not true", limelight.hasTarget());
}
}

0 comments on commit 3db9b65

Please sign in to comment.