Skip to content

Commit

Permalink
Prepare for release
Browse files Browse the repository at this point in the history
  • Loading branch information
Mason-Lam committed Apr 15, 2024
1 parent a6b8b1d commit fe5cebc
Show file tree
Hide file tree
Showing 9 changed files with 69 additions and 86 deletions.
4 changes: 2 additions & 2 deletions 3128-Common.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"name": "3128-common",
"version": "1.7.3",
"version": "1.7.4",
"uuid": "ae3fa5a2-78d9-47e8-921a-dba45b889445",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,7 +12,7 @@
{
"groupId": "com.github.Team3128",
"artifactId": "3128-common",
"version": "1.7.3"
"version": "1.7.4"
}
],
"jniDependencies": [],
Expand Down
4 changes: 2 additions & 2 deletions 3128-common.json
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
{
"name": "3128-common",
"version": "1.7.3",
"version": "1.7.4",
"uuid": "ae3fa5a2-78d9-47e8-921a-dba45b889445",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -12,7 +12,7 @@
{
"groupId": "com.github.Team3128",
"artifactId": "3128-common",
"version": "1.7.3"
"version": "1.7.4"
}
],
"jniDependencies": [],
Expand Down
91 changes: 41 additions & 50 deletions doc/common/hardware/camera/Camera.html

Large diffs are not rendered by default.

8 changes: 3 additions & 5 deletions doc/index-all.html
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ <h2 class="title" id="I:A">A</h2>
<dd>
<div class="block">Displays sendable values, like subsystems and command, works on all classes that extend sendable</div>
</dd>
<dt><a href="common/hardware/camera/Camera.html#addShootTags(int...)" class="member-name-link">addShootTags(int...)</a> - Static method in class common.hardware.camera.<a href="common/hardware/camera/Camera.html" title="class in common.hardware.camera">Camera</a></dt>
<dt><a href="common/hardware/camera/Camera.html#addTags(int...)" class="member-name-link">addTags(int...)</a> - Static method in class common.hardware.camera.<a href="common/hardware/camera/Camera.html" title="class in common.hardware.camera">Camera</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/utility/tester/Tester.Test.html#addTest(common.utility.tester.Tester.Test)" class="member-name-link">addTest(Tester.Test)</a> - Method in class common.utility.tester.<a href="common/utility/tester/Tester.Test.html" title="class in common.utility.tester">Tester.Test</a></dt>
<dd>
Expand Down Expand Up @@ -194,8 +194,6 @@ <h2 class="title" id="I:A">A</h2>
<dd>&nbsp;</dd>
<dt><a href="common/hardware/limelight/LimelightKey.html#AREA" class="member-name-link">AREA</a> - Enum constant in enum class common.hardware.limelight.<a href="common/hardware/limelight/LimelightKey.html" title="enum class in common.hardware.limelight">LimelightKey</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/hardware/camera/Camera.html#areShootTagsSeen" class="member-name-link">areShootTagsSeen</a> - Static variable in class common.hardware.camera.<a href="common/hardware/camera/Camera.html" title="class in common.hardware.camera">Camera</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/core/controllers/ControllerBase.html#atSetpoint()" class="member-name-link">atSetpoint()</a> - Method in class common.core.controllers.<a href="common/core/controllers/ControllerBase.html" title="class in common.core.controllers">ControllerBase</a></dt>
<dd>
<div class="block">Returns true if the error is within the tolerance of the setpoint.</div>
Expand Down Expand Up @@ -306,8 +304,6 @@ <h2 class="title" id="I:C">C</h2>
<dd>&nbsp;</dd>
<dt><a href="common/core/swerve/SwerveBase.html#chassisVelocityCorrection" class="member-name-link">chassisVelocityCorrection</a> - Variable in class common.core.swerve.<a href="common/core/swerve/SwerveBase.html" title="class in common.core.swerve">SwerveBase</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/hardware/camera/Camera.html#checkShootTagsAll()" class="member-name-link">checkShootTagsAll()</a> - Static method in class common.hardware.camera.<a href="common/hardware/camera/Camera.html" title="class in common.hardware.camera">Camera</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/utility/narwhaldashboard/NarwhalDashboard.html#checkState(java.lang.String,java.util.function.Supplier)" class="member-name-link">checkState(String, Supplier&lt;NarwhalDashboard.State&gt;)</a> - Method in class common.utility.narwhaldashboard.<a href="common/utility/narwhaldashboard/NarwhalDashboard.html" title="class in common.utility.narwhaldashboard">NarwhalDashboard</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/utility/sysid/FFCharacterization.html#clear()" class="member-name-link">clear()</a> - Method in class common.utility.sysid.<a href="common/utility/sysid/FFCharacterization.html" title="class in common.utility.sysid">FFCharacterization</a></dt>
Expand Down Expand Up @@ -1697,6 +1693,8 @@ <h2 class="title" id="I:S">S</h2>
<dd>&nbsp;</dd>
<dt><a href="common/hardware/limelight/LimelightConstants.html#SCREEN_WIDTH" class="member-name-link">SCREEN_WIDTH</a> - Static variable in class common.hardware.limelight.<a href="common/hardware/limelight/LimelightConstants.html" title="class in common.hardware.limelight">LimelightConstants</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/hardware/camera/Camera.html#seesTag()" class="member-name-link">seesTag()</a> - Static method in class common.hardware.camera.<a href="common/hardware/camera/Camera.html" title="class in common.hardware.camera">Camera</a></dt>
<dd>&nbsp;</dd>
<dt><a href="common/utility/narwhaldashboard/NarwhalDashboard.html#sendMessage(java.lang.String)" class="member-name-link">sendMessage(String)</a> - Method in class common.utility.narwhaldashboard.<a href="common/utility/narwhaldashboard/NarwhalDashboard.html" title="class in common.utility.narwhaldashboard">NarwhalDashboard</a></dt>
<dd>
<div class="block">Sends a message to console.log on Narwhal Dashboard.</div>
Expand Down
2 changes: 1 addition & 1 deletion doc/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ <h1 class="title">3128-common</h1>
</div>
<div class="block"><h1>FRC Team 3128 Robot Control Program Utility Library</h1>
<p>Provides utility classes and functions for FRC robot control programs.</p>
<p>Version 1.7.3 (April 13 2024)</p></div>
<p>Version 1.7.4 (April 13 2024)</p></div>
<div id="all-packages-table">
<div class="caption"><span>Packages</span></div>
<div class="summary-table two-column-summary">
Expand Down
2 changes: 1 addition & 1 deletion doc/member-search-index.js

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion gradle.properties
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
LibraryVersion=1.7.3
LibraryVersion=1.7.4
archivesGroup = com.github.Team3128
archivesBaseName = 3128-common
jsonFileName = 3128-common.json
Expand Down
40 changes: 17 additions & 23 deletions src/main/java/common/hardware/camera/Camera.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,6 @@
import java.util.function.BiConsumer;
import java.util.function.Supplier;
import java.util.ArrayList;
import java.util.HashMap;

import org.littletonrobotics.junction.Logger;
import org.photonvision.EstimatedRobotPose;
import org.photonvision.PhotonCamera;
Expand All @@ -32,16 +30,14 @@
*/
public class Camera {

public static boolean areShootTagsSeen = false;

private static ArrayList<Integer> shootTags = new ArrayList<Integer>();
private static ArrayList<Integer> tags = new ArrayList<Integer>();

private static HashMap<Camera, Boolean> shootTagsSeen = new HashMap<Camera, Boolean>();
private boolean hasSeenTag;

public static int updateCounter = 0;

public static double validDist = 0.5;
public static double overrideThreshold = 30;
public static double overrideThreshold = 5;

private final PhotonCamera camera;
private final Transform3d offset;
Expand All @@ -54,7 +50,7 @@ public class Camera {
private static PoseStrategy calc_strategy;
private static BiConsumer<Pose2d, Double> odometry;
private static Supplier<Pose2d> robotPose;
private static double ambiguityThreshold = 0.2;
private static double ambiguityThreshold = 0.3;

private static ArrayList<Integer> ignoredTags = new ArrayList<Integer>();

Expand All @@ -78,7 +74,7 @@ public Camera(String name, double xOffset, double yOffset, double yawOffset, dou
}

cameras.add(this);
shootTagsSeen.put(this, false);
hasSeenTag = false;
}

public static void configCameras(AprilTagFields aprilTagLayout, PoseStrategy calc_strategy, BiConsumer<Pose2d, Double> odometry, Supplier<Pose2d> robotPose){
Expand All @@ -94,20 +90,17 @@ public static void addIgnoredTags(int ...ignoredTags) {
}
}

public static void addShootTags(int ...shootTags) {
for(final int tag : shootTags) {
Camera.shootTags.add(tag);
public static void addTags(int ...tags) {
for(final int tag : tags) {
Camera.tags.add(tag);
}
}

public static void checkShootTagsAll(){
public static boolean seesTag(){
for (final Camera camera : cameras) {
if(shootTagsSeen.get(camera)) {
areShootTagsSeen = true;
return;
}
if(camera.hasSeenTag) return true;
}
areShootTagsSeen = false;
return false;
}

public static void updateAll(){
Expand Down Expand Up @@ -153,13 +146,10 @@ private Optional<EstimatedRobotPose> getEstimatedPose(PhotonPipelineResult resul
if (dist > distanceThreshold || targetPoseAmbiguity > ambiguityThreshold || ignoredTags.contains(Integer.valueOf(target.getFiducialId()))) continue;
// Make sure the target is a Fiducial target.

if(shootTags.contains(Integer.valueOf(target.getFiducialId()))) {
shootTagsSeen.put(this, true);
}

if (targetPoseAmbiguity != -1 && targetPoseAmbiguity < lowestAmbiguityScore) {
lowestAmbiguityScore = targetPoseAmbiguity;
lowestAmbiguityTarget = target;
hasSeenTag = tags.contains(target.getFiducialId());
}
}

Expand Down Expand Up @@ -200,6 +190,7 @@ private void reportFiducialPoseError(int fiducialId) {

public void update(){
if (isDisabled) return;
hasSeenTag = false;
lastResult = camera.getLatestResult();
if (!lastResult.hasTargets() && NAR_Robot.logWithAdvantageKit) {
Logger.recordOutput("Vision/" + camera.getName() + "/Position", robotPose.get());
Expand All @@ -217,7 +208,10 @@ public void update(){

if(!isGoodEstimate(estPose)) {
updateCounter++;
if (updateCounter <= overrideThreshold) return;
if (updateCounter <= overrideThreshold) {
hasSeenTag = false;
return;
}
}
else {
updateCounter = 0;
Expand Down
2 changes: 1 addition & 1 deletion src/main/resources/overview.html
Original file line number Diff line number Diff line change
Expand Up @@ -8,5 +8,5 @@
<body>
<h1>FRC Team 3128 Robot Control Program Utility Library</h1>
<p>Provides utility classes and functions for FRC robot control programs.</p>
<p>Version 1.7.3 (April 13 2024)</p>
<p>Version 1.7.4 (April 13 2024)</p>
</body>

0 comments on commit fe5cebc

Please sign in to comment.