Skip to content

Commit

Permalink
Began adding simulation.
Browse files Browse the repository at this point in the history
  • Loading branch information
thenetworkgrinch committed Jan 25, 2025
1 parent 7abb7a4 commit d0df476
Show file tree
Hide file tree
Showing 24 changed files with 151 additions and 92 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,13 @@
import java.util.Optional;
import java.util.function.DoubleSupplier;
import limelight.Limelight;
import limelight.estimator.LimelightPoseEstimator;
import limelight.estimator.PoseEstimate;
import limelight.structures.AngularVelocity3d;
import limelight.structures.LimelightResults;
import limelight.structures.LimelightSettings.LEDMode;
import limelight.structures.Orientation3d;
import limelight.structures.target.pipeline.NeuralClassifier;
import limelight.networktables.AngularVelocity3d;
import limelight.networktables.LimelightPoseEstimator;
import limelight.networktables.LimelightResults;
import limelight.networktables.LimelightSettings.LEDMode;
import limelight.networktables.Orientation3d;
import limelight.networktables.PoseEstimate;
import limelight.networktables.target.pipeline.NeuralClassifier;

public class DrivebaseSubsystem extends SubsystemBase
{
Expand Down
15 changes: 8 additions & 7 deletions yall/java/limelight/Limelight.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,22 +3,23 @@

import static edu.wpi.first.units.Units.Milliseconds;
import static edu.wpi.first.units.Units.Seconds;
import static limelight.structures.LimelightUtils.getLimelightURLString;
import static limelight.networktables.LimelightUtils.getLimelightURLString;

import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj.RobotBase;
import java.io.IOException;
import java.net.HttpURLConnection;
import java.net.URL;
import java.util.Optional;
import java.util.concurrent.CompletableFuture;
import java.util.stream.Collectors;
import limelight.estimator.LimelightPoseEstimator;
import limelight.structures.LimelightData;
import limelight.structures.LimelightResults;
import limelight.structures.LimelightSettings;
import limelight.networktables.LimelightData;
import limelight.networktables.LimelightPoseEstimator;
import limelight.networktables.LimelightResults;
import limelight.networktables.LimelightSettings;

/**
* Limelight Camera class.
Expand Down Expand Up @@ -47,7 +48,7 @@ public class Limelight
*/
public Limelight(String name)
{
if (!isAvailable(name))
if (!isAvailable(name) && !RobotBase.isSimulation())
{
throw new RuntimeException("Limelight not available");
}
Expand Down Expand Up @@ -123,7 +124,7 @@ public LimelightPoseEstimator getPoseEstimator(boolean megatag2)
*
* @return object used as the target of the various ".withXXXX" settings methods.
*/
public LimelightSettings settingsBuilder()
public LimelightSettings getSettings()
{
return settings;
}
Expand Down
4 changes: 0 additions & 4 deletions yall/java/limelight/estimator/package-info.java

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package limelight.structures;
package limelight.networktables;

import edu.wpi.first.units.measure.AngularVelocity;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package limelight.structures;
package limelight.networktables;


import static limelight.structures.LimelightUtils.extractArrayEntry;
import static limelight.structures.LimelightUtils.toPose3D;
import static limelight.networktables.LimelightUtils.extractArrayEntry;
import static limelight.networktables.LimelightUtils.toPose3D;

import com.fasterxml.jackson.databind.DeserializationFeature;
import com.fasterxml.jackson.databind.ObjectMapper;
Expand Down Expand Up @@ -34,51 +34,51 @@ public class LimelightData
/**
* {@link NetworkTable} for the {@link Limelight}
*/
private NetworkTable limelightTable;
protected NetworkTable limelightTable;
/**
* {@link Limelight} to fetch data for.
*/
private Limelight limelight;
/**
* The limelight.results {@link LimelightResults} JSON data
*/
private NetworkTableEntry results;
protected NetworkTableEntry results;
/**
* Raw AprilTag detection from NetworkTables.
*/
private NetworkTableEntry rawfiducials;
protected NetworkTableEntry rawfiducials;
/**
* Raw Neural Detector limelight.results from NetworkTables.
*/
private NetworkTableEntry rawDetections;
protected NetworkTableEntry rawDetections;
/**
* Neural Clasifier result class name.
*/
private NetworkTableEntry classifierClass;
protected NetworkTableEntry classifierClass;
/**
* Primary neural detect result class name.
*/
private NetworkTableEntry detectorClass;
protected NetworkTableEntry detectorClass;
/**
* {@link Pose3d} object representing the camera's position and orientation relative to the robot.
*/
private DoubleArrayEntry camera2RobotPose3d;
protected DoubleArrayEntry camera2RobotPose3d;
/**
* Barcodes read by the {@link Limelight}.
*/
private StringArrayEntry barcodeData;
protected StringArrayEntry barcodeData;
/**
* Custom Python script set data for {@link Limelight}.
*/
private DoubleArrayEntry pythonScriptDataSet;
protected DoubleArrayEntry pythonScriptDataSet;
/**
* Custom Python script output data for {@link Limelight}.
*/
private DoubleArrayEntry pythonScriptData;
protected DoubleArrayEntry pythonScriptData;
/**
* Object mapper for limelight.results JSON.
*/
private ObjectMapper resultsObjectMapper;
protected ObjectMapper resultsObjectMapper;

/**
* Construct the {@link LimelightData} class to retrieve read-only data.
Expand Down Expand Up @@ -182,7 +182,6 @@ public Optional<LimelightResults> getResults()
}
LimelightResults data = resultsObjectMapper.readValue(JSONresult,
LimelightResults.class); // don't use wrapper class
// LimelightResults data = resultsObjectMapper.readValue(JSONresult, ResultsWrapper.class).resultsWrapper; // use wrapper class
return Optional.of(data);
} catch (Exception e) // catch all the errors - multiple kinds are possible
{
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package limelight.structures;
package limelight.networktables;


import edu.wpi.first.networktables.NetworkTable;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
package limelight.estimator;
package limelight.networktables;


import static limelight.structures.LimelightUtils.toPose3D;
import static limelight.networktables.LimelightUtils.toPose3D;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.networktables.DoubleArrayEntry;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package limelight.structures;
package limelight.networktables;


import static limelight.structures.LimelightUtils.toPose2D;
import static limelight.structures.LimelightUtils.toPose3D;
import static limelight.networktables.LimelightUtils.toPose2D;
import static limelight.networktables.LimelightUtils.toPose3D;

import com.fasterxml.jackson.annotation.JsonFormat;
import com.fasterxml.jackson.annotation.JsonFormat.Shape;
Expand All @@ -11,11 +11,11 @@
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.wpilibj.DriverStation;
import limelight.Limelight;
import limelight.structures.target.AprilTagFiducial;
import limelight.structures.target.Barcode;
import limelight.structures.target.RetroreflectiveTape;
import limelight.structures.target.pipeline.NeuralClassifier;
import limelight.structures.target.pipeline.NeuralDetector;
import limelight.networktables.target.AprilTagFiducial;
import limelight.networktables.target.Barcode;
import limelight.networktables.target.RetroreflectiveTape;
import limelight.networktables.target.pipeline.NeuralClassifier;
import limelight.networktables.target.pipeline.NeuralDetector;

/**
* {@link Limelight} Results object, parsed from a {@link Limelight}'s JSON limelight.results output.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package limelight.structures;
package limelight.networktables;

import static limelight.structures.LimelightUtils.orientation3dToArray;
import static limelight.structures.LimelightUtils.pose3dToArray;
import static limelight.structures.LimelightUtils.translation3dToArray;
import static limelight.networktables.LimelightUtils.orientation3dToArray;
import static limelight.networktables.LimelightUtils.pose3dToArray;
import static limelight.networktables.LimelightUtils.translation3dToArray;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Translation3d;
Expand Down
84 changes: 84 additions & 0 deletions yall/java/limelight/networktables/LimelightSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
package limelight.networktables;

import static edu.wpi.first.units.Units.Meters;

import com.fasterxml.jackson.core.JsonProcessingException;
import edu.wpi.first.apriltag.AprilTag;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rectangle2d;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.units.measure.Distance;
import java.util.List;
import java.util.function.Supplier;
import limelight.Limelight;
import limelight.networktables.target.AprilTagFiducial;

public class LimelightSim
{

private Limelight m_limelight;
private Supplier<Pose2d> m_pose;
private AprilTagFieldLayout m_fieldLayout;
private NetworkTable m_limelightTable;
private Distance m_limelightViewDistance = Meters.of(1);

/**
* Limelight simulation class
*
* @param limelight {@link Limelight} to use.
* @param odomPose Supplier of the odom pose.
* @param fieldLayout {@link AprilTagFieldLayout} to use.
*/
public LimelightSim(Limelight limelight, Supplier<Pose2d> odomPose, AprilTagFieldLayout fieldLayout)
{
m_limelight = limelight;
m_pose = odomPose;
m_fieldLayout = fieldLayout;
m_limelightTable = NetworkTableInstance.getDefault().getTable(limelight.limelightName);

}

/**
* Gets the {@link AprilTag} in view of the Limelight, does this by using a Rectangle bounding box from your current
* pose.
*
* @return List of {@link AprilTag}s in range
*/
public List<AprilTag> getAprilTagsInView()
{
Rectangle2d viewbox = new Rectangle2d(m_pose.get(), m_limelightViewDistance, m_limelightViewDistance);
// TODO: Improve this to use a triangular cone FOV.
return m_fieldLayout.getTags().stream()
.filter(aprilTag -> viewbox.contains(aprilTag.pose.toPose2d().getTranslation()))
.toList();
}


public void updateTagKeys()
{
LimelightData data = m_limelight.getData();
List<AprilTag> tags = getAprilTagsInView();
LimelightResults llJson = new LimelightResults();
llJson.botpose = LimelightUtils.pose2dToArray(m_pose.get());
llJson.valid = true;
llJson.targets_Fiducials = (AprilTagFiducial[]) (tags.stream().map(aprilTag -> {
AprilTagFiducial fid = new AprilTagFiducial();
fid.fiducialID = aprilTag.ID;
fid.fiducialFamily = "36h11";
return fid;
}).toArray());
try
{
data.results.setString(data.resultsObjectMapper.writer().withDefaultPrettyPrinter().writeValueAsString(llJson));
} catch (JsonProcessingException e)
{
throw new RuntimeException(e);
}
// TODO: Expand this to implement more of the ll json.

}


}
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
package limelight.structures;
package limelight.networktables;


import static limelight.structures.LimelightUtils.toPose3D;
import static limelight.networktables.LimelightUtils.toPose3D;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.networktables.DoubleArrayEntry;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package limelight.structures;
package limelight.networktables;


import static edu.wpi.first.units.Units.Degrees;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package limelight.structures;
package limelight.networktables;

import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.units.measure.AngularVelocity;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package limelight.estimator;
package limelight.networktables;


import static limelight.structures.LimelightUtils.extractArrayEntry;
import static limelight.structures.LimelightUtils.toPose3D;
import static limelight.networktables.LimelightUtils.extractArrayEntry;
import static limelight.networktables.LimelightUtils.toPose3D;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.networktables.DoubleArrayEntry;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/**
* All Structures and utilities relating to Limelight NetworkTable data.
*/
package limelight.structures;
package limelight.networktables;
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
package limelight.structures.target;
package limelight.networktables.target;

import static limelight.structures.LimelightUtils.toPose2D;
import static limelight.structures.LimelightUtils.toPose3D;
import static limelight.networktables.LimelightUtils.toPose2D;
import static limelight.networktables.LimelightUtils.toPose3D;

import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.geometry.Pose2d;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package limelight.structures.target;
package limelight.networktables.target;

import com.fasterxml.jackson.annotation.JsonProperty;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
package limelight.structures.target;
package limelight.networktables.target;

import static limelight.structures.LimelightUtils.toPose2D;
import static limelight.structures.LimelightUtils.toPose3D;
import static limelight.networktables.LimelightUtils.toPose2D;
import static limelight.networktables.LimelightUtils.toPose3D;

import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.math.geometry.Pose2d;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/**
* Target data structures mapped to NetworkTables data.
*/
package limelight.structures.target;
package limelight.networktables.target;
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package limelight.structures.target.pipeline;
package limelight.networktables.target.pipeline;

import com.fasterxml.jackson.annotation.JsonProperty;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package limelight.structures.target.pipeline;
package limelight.networktables.target.pipeline;

import com.fasterxml.jackson.annotation.JsonProperty;

Expand Down
Loading

0 comments on commit d0df476

Please sign in to comment.