Skip to content

Commit

Permalink
Merge pull request #3 from CelestialWren/main
Browse files Browse the repository at this point in the history
  • Loading branch information
thenetworkgrinch authored Jan 25, 2025
2 parents d0df476 + d209dc1 commit 1091b19
Showing 1 changed file with 39 additions and 1 deletion.
40 changes: 39 additions & 1 deletion yall/java/limelight/networktables/LimelightSettings.java
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,10 @@ public class LimelightSettings
* [cropXMin,cropXMax,cropYMin,cropYMax] values between -1 and 1
*/
private DoubleArrayEntry cropWindow;
/**
* Imu Mode for the Limelight 4.
*/
private NetworkTableEntry imuMode;
/**
* Sets 3d offset point for easy 3d targeting Sets the 3D point-of-interest offset for the current fiducial pipeline.
* <p>
Expand Down Expand Up @@ -104,6 +108,7 @@ public LimelightSettings(Limelight camera)
priorityTagID = limelightTable.getEntry("priorityid");
streamMode = limelightTable.getEntry("stream");
cropWindow = limelightTable.getDoubleArrayTopic("crop").getEntry(new double[0]);
imuMode = limelightTable.getEntry("imumode_set");
robotOrientationSet = limelightTable.getDoubleArrayTopic("robot_orientation_set").getEntry(new double[0]);
downscale = limelightTable.getEntry("fiducial_downscale_set");
fiducial3DOffset = limelightTable.getDoubleArrayTopic("fiducial_offset_set").getEntry(new double[0]);
Expand Down Expand Up @@ -154,7 +159,7 @@ public LimelightSettings withPriorityTagId(int aprilTagId)
* Set the Stream mode based on the {@link StreamMode} enum
* <p> This method changes the Limelight - normally immediately.
*
* @param mode {@link StreamMode} to use
* @param mode {@link StreamMode} to use.
* @return {@link LimelightSettings} for chaining.
*/
public LimelightSettings withStreamMode(StreamMode mode)
Expand All @@ -171,13 +176,27 @@ public LimelightSettings withStreamMode(StreamMode mode)
* @param maxX Maximum X value (-1 to 1)
* @param minY Minimum Y value (-1 to 1)
* @param maxY Maximum Y value (-1 to 1)
* @return {@link LimelightSettings} for chaining.
*/
public LimelightSettings withCropWindow(double minX, double maxX, double minY, double maxY)
{
cropWindow.set(new double[]{minX, maxX, minY, maxY});
return this;
}

/**
* Set the IMU Mode based on the {@link ImuMode} enum.
* <p> This method changes the Limelight - normally immediately.
*
* @param mode {@link ImuMode} to use.
* @return {@link LimelightSettings} for chaining.
*/
public LimelightSettings withImuMode(ImuMode mode)
{
imuMode.setNumber(mode.ordinal());
return this;
}

/**
* Set the current robot {@link Orientation3d} (normally given by the robot gyro) for LL to use in its MegaTag2
* determination.
Expand All @@ -199,6 +218,7 @@ public LimelightSettings withRobotOrientation(Orientation3d orientation)
*
* @param downscalingOverride Downscale factor. Valid values: 1.0 (no downscale), 1.5, 2.0, 3.0, 4.0. Set to 0 for
* pipeline control.
* @return {@link LimelightSettings} for chaining.
*/
public LimelightSettings withFiducialDownscalingOverride(DownscalingOverride downscalingOverride)
{
Expand Down Expand Up @@ -321,5 +341,23 @@ public enum DownscalingOverride
*/
QuadrupleDownscale
}
/**
* IMU Mode Enum for the {@link Limelight}
*/
public enum ImuMode
{
/**
* Use external IMU yaw submitted via {@link withRobotOrientation} for MT2 localization. The internal IMU is ignored entirely.
*/
ExternalImu,
/**
* Use external IMU yaw submitted via {@link withRobotOrientation} for MT2 localization. The internal IMU is synced with the external IMU.
*/
SyncInternalImu,
/**
* Use internal IMU for MT2 localization. Ignores external IMU updates from {@link withRobotOrientation}.
*/
InternalImu
}

}

0 comments on commit 1091b19

Please sign in to comment.