Skip to content

Commit

Permalink
hide ATFL setter
Browse files Browse the repository at this point in the history
  • Loading branch information
amquake committed Oct 25, 2023
1 parent 78bbd19 commit e531236
Show file tree
Hide file tree
Showing 2 changed files with 43 additions and 37 deletions.
75 changes: 39 additions & 36 deletions photon-lib/src/main/java/org/photonvision/PhotonCamera.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,9 @@

package org.photonvision;

import com.fasterxml.jackson.core.JsonProcessingException;
import com.fasterxml.jackson.databind.ObjectMapper;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.math.MatBuilder;
import edu.wpi.first.math.MathSharedStore;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.Nat;
import edu.wpi.first.math.numbers.*;
Expand Down Expand Up @@ -335,39 +332,45 @@ public boolean isConnected() {
return (now - prevHeartbeatChangeTime) < HEARBEAT_DEBOUNCE_SEC;
}

/**
* Get the last set {@link AprilTagFieldLayout}. The tag layout is shared between all PhotonVision
* coprocessors on the same NT instance-- this method returns the most recent layout set. If no
* layout has been set by the user, this is equal to {@link AprilTagFields#kDefaultField}.
*
* @return The last set layout
*/
public AprilTagFieldLayout getAprilTagFieldLayout() {
return lastSetTagLayout;
}

/**
* Set the {@link AprilTagFieldLayout} used by all PhotonVision coprocessors that are (or might
* later) connect to this robot. The topic is marked as persistent, so even if you only call this
* once ever, it will be saved on the RoboRIO and pushed out to all NT clients when code reboots.
* PhotonVision will also store a copy of this layout locally on the coprocessor, but subscribes
* to this topic and the local copy will be updated when this function is called.
*
* @param layout The layout to use for *all* PhotonVision cameras
* @return Success of serializing the JSON. This does *not* mean that all PhotonVision clients
* have updated their internal layouts.
*/
public boolean setAprilTagFieldLayout(AprilTagFieldLayout layout) {
try {
var layout_json = new ObjectMapper().writeValueAsString(layout);
atflPublisher.set(layout_json);
lastSetTagLayout = layout;
return true;
} catch (JsonProcessingException e) {
MathSharedStore.reportError("Error setting ATFL in " + this.getName(), e.getStackTrace());
}
return false;
}
// TODO: Implement ATFL subscribing in backend
// /**
// * Get the last set {@link AprilTagFieldLayout}. The tag layout is shared between all
// PhotonVision
// * coprocessors on the same NT instance-- this method returns the most recent layout set. If no
// * layout has been set by the user, this is equal to {@link AprilTagFields#kDefaultField}.
// *
// * @return The last set layout
// */
// public AprilTagFieldLayout getAprilTagFieldLayout() {
// return lastSetTagLayout;
// }

// /**
// * Set the {@link AprilTagFieldLayout} used by all PhotonVision coprocessors that are (or might
// * later) connect to this robot. The topic is marked as persistent, so even if you only call
// this
// * once ever, it will be saved on the RoboRIO and pushed out to all NT clients when code
// reboots.
// * PhotonVision will also store a copy of this layout locally on the coprocessor, but
// subscribes
// * to this topic and the local copy will be updated when this function is called.
// *
// * @param layout The layout to use for *all* PhotonVision cameras
// * @return Success of serializing the JSON. This does *not* mean that all PhotonVision clients
// * have updated their internal layouts.
// */
// public boolean setAprilTagFieldLayout(AprilTagFieldLayout layout) {
// try {
// var layout_json = new ObjectMapper().writeValueAsString(layout);
// atflPublisher.set(layout_json);
// lastSetTagLayout = layout;
// return true;
// } catch (JsonProcessingException e) {
// MathSharedStore.reportError("Error setting ATFL in " + this.getName(),
// e.getStackTrace());
// }
// return false;
// }

public Optional<Matrix<N3, N3>> getCameraMatrix() {
var cameraMatrix = cameraIntrinsicsSubscriber.get();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@

package org.photonvision.simulation;

import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.cscore.CvSource;
import edu.wpi.first.cscore.VideoMode.PixelFormat;
Expand Down Expand Up @@ -529,7 +530,9 @@ public PhotonPipelineResult process(

// calculate multitag results
var multitagResults = new MultiTargetPNPResults();
var tagLayout = cam.getAprilTagFieldLayout();
// TODO: Implement ATFL subscribing in backend
// var tagLayout = cam.getAprilTagFieldLayout();
var tagLayout = AprilTagFields.kDefaultField.loadAprilTagLayoutField();
var visibleLayoutTags = VisionEstimation.getVisibleLayoutTags(detectableTgts, tagLayout);
if (visibleLayoutTags.size() > 1) {
List<Integer> usedIDs =
Expand Down

0 comments on commit e531236

Please sign in to comment.