Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Better PhotonCamera #132

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion checks.xml
Original file line number Diff line number Diff line change
Expand Up @@ -319,7 +319,7 @@
value="^@return the *|^This method returns |^A [{]@code [_a-zA-Z0-9]+[}]( is a )"/>
</module> -->
<module name="JavadocParagraph">
<property name="allowNewlineParagraph" value="false"/>
<property name="allowNewlineParagraph" value="true"/>
</module>
<module name="JavadocStyle">
<property name="checkFirstSentence" value="false"/>
Expand Down
164 changes: 164 additions & 0 deletions src/main/java/frc/lib/util/photon/LoggedPhotonCamera.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,164 @@
package frc.lib.util.photon;

import java.io.File;
import java.io.IOException;
import java.io.InputStream;
import java.nio.charset.StandardCharsets;
import java.util.Optional;
import java.util.concurrent.atomic.AtomicBoolean;
import org.apache.http.HttpEntity;
import org.apache.http.client.methods.CloseableHttpResponse;
import org.apache.http.client.methods.HttpPost;
import org.apache.http.entity.mime.MultipartEntityBuilder;
import org.apache.http.entity.mime.content.FileBody;
import org.apache.http.impl.client.CloseableHttpClient;
import org.apache.http.impl.client.HttpClients;
import org.littletonrobotics.junction.LogTable;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.inputs.LoggableInputs;
import org.photonvision.PhotonCamera;
import org.photonvision.common.dataflow.structures.Packet;
import org.photonvision.targeting.PhotonPipelineResult;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.numbers.N5;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/** PhotonCamera modified to work with AdvantageKit */
public class LoggedPhotonCamera extends PhotonCamera {

/** Inputs for LoggedPhotonCamera */
public static class PhotonCameraInputs implements LoggableInputs, Cloneable {
public PhotonPipelineResult result = null;
public Optional<Matrix<N3, N3>> cameraMatrix = Optional.empty();
public Optional<Matrix<N5, N1>> distCoeffs = Optional.empty();
public String name = "";

@Override
public void toLog(LogTable table) {
if (result == null) {
var rawBytes = new byte[0];
table.put("rawBytes", rawBytes);
} else {
// https://github.com/PhotonVision/photonvision/blob/471c90e8fabc55aad039bb712df7dcc11d12fc6b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java#L144
var rawBytes = new Packet(1024);
PhotonPipelineResult.serde.pack(rawBytes, result);
table.put("rawBytes", rawBytes.getData());
}
if (cameraMatrix.isPresent()) {
table.put("cameraMatrix", cameraMatrix.get().getData());
} else {
table.put("cameraMatrix", new double[0]);
}
if (distCoeffs.isPresent()) {
table.put("distCoeffs", distCoeffs.get().getData());
} else {
table.put("distCoeffs", new double[0]);
}
}

@Override
public void fromLog(LogTable table) {
var rawBytes = table.get("rawBytes", new byte[0]);
if (rawBytes.length > 0) {
Packet p = new Packet(rawBytes);
this.result = PhotonPipelineResult.serde.unpack(p);
} else {
this.result = null;
}

double[] data = table.get("cameraMatrix", new double[0]);
if (data.length == 0) {
this.cameraMatrix = Optional.empty();
} else {
this.cameraMatrix = Optional.of(new Matrix<>(N3.instance, N3.instance, data));
}
data = table.get("distCoeffs", new double[0]);
if (data.length == 0) {
this.distCoeffs = Optional.empty();
} else {
this.distCoeffs = Optional.of(new Matrix<>(N5.instance, N1.instance, data));
}
}

}

private final PhotonCameraInputs inputs = new PhotonCameraInputs();

/** Create PhotonCamera with a given name and IP. */
public LoggedPhotonCamera(String cameraName, String cameraIP) {
super(cameraName);
inputs.name = cameraName;
new Thread(() -> {
Timer timer = new Timer();
while (true) {
if (timer.advanceIfElapsed(10.0) && !isPhotonOk.get()) {
try {
uploadSettings(cameraIP + ":5800",
new File(Filesystem.getDeployDirectory().getAbsoluteFile(),
"photon-configs/" + cameraName + ".zip"));
} catch (IOException e) {
e.printStackTrace();
}
}
Thread.yield();
}
}).start();
}
Comment on lines +95 to +110
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should only do this if in simulation mode.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Probably. Agreed on the separate "Vision" subsystem.


/** Update inputs for this camera. */
public void periodic() {
this.inputs.result = super.getLatestResult();
this.inputs.cameraMatrix = super.getCameraMatrix();
this.inputs.distCoeffs = super.getDistCoeffs();
Logger.processInputs("Camera_" + this.inputs.name, inputs);
this.isPhotonOk.set(this.inputs.distCoeffs.isPresent());
}

@Override
public PhotonPipelineResult getLatestResult() {
return this.inputs.result;
}

@Override
public Optional<Matrix<N3, N3>> getCameraMatrix() {
return this.inputs.cameraMatrix;
}

@Override
public Optional<Matrix<N5, N1>> getDistCoeffs() {
return this.inputs.distCoeffs;
}

private boolean uploadSettings(String ip, File file) throws IOException {
try (final CloseableHttpClient httpClient = HttpClients.createDefault()) {
HttpPost postReq = new HttpPost("http://" + ip + "/api/settings");
HttpEntity entity =
MultipartEntityBuilder.create().addPart("data", new FileBody(file)).build();
postReq.setEntity(entity);
try (CloseableHttpResponse response = httpClient.execute(postReq)) {
SmartDashboard.putString("uploadSettings/" + this.inputs.name + "/status",
response.getStatusLine().getStatusCode() + ": "
+ response.getStatusLine().getReasonPhrase());
var ent = response.getEntity();
if (ent != null) {
try (InputStream stream = ent.getContent()) {
String text = new String(stream.readAllBytes(), StandardCharsets.UTF_8);
SmartDashboard.putString("uploadSettings/" + this.inputs.name + "/content",
text);
}
} else {
SmartDashboard.putString("uploadSettings/" + this.inputs.name + "/content",
"null");
}
return response.getStatusLine().getStatusCode() == 200;
}
}
}

private AtomicBoolean isPhotonOk = new AtomicBoolean(false);

}
50 changes: 14 additions & 36 deletions src/main/java/frc/lib/util/photon/PhotonCameraWrapper.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.lib.util.photon;

import java.util.Optional;
import org.littletonrobotics.junction.Logger;
import org.photonvision.EstimatedRobotPose;
import org.photonvision.PhotonPoseEstimator;
import org.photonvision.PhotonPoseEstimator.PoseStrategy;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
Expand All @@ -16,67 +16,45 @@
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.lib.util.photon.PhotonIO.PhotonInputs;
import frc.robot.Constants;

/**
* PhotonCamera-based Pose Estimator.
*/
public class PhotonCameraWrapper {
public PhotonIO io;
public PhotonInputs inputs = new PhotonInputs();
public PhotonIOPoseEstimator photonPoseEstimator;
private double resetTimer = 0;
public LoggedPhotonCamera camera;
private PhotonPoseEstimator photonPoseEstimator;

/**
* PhotonCamera-based Pose Estimator.
*
* @param io Camera IO.
* @param robotToCam transform from robot body coordinates to camera coordinates.
*/
public PhotonCameraWrapper(PhotonIO io, Transform3d robotToCam) {
this.io = io;
public PhotonCameraWrapper(String name, String cameraIP, Transform3d robotToCam) {
this.camera = new LoggedPhotonCamera(name, cameraIP);

// Attempt to load the AprilTagFieldLayout that will tell us where the tags are on the
// field.
AprilTagFieldLayout fieldLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField();
// Create pose estimator
photonPoseEstimator = new PhotonIOPoseEstimator(fieldLayout,
PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, this.inputs, robotToCam);
photonPoseEstimator = new PhotonPoseEstimator(fieldLayout,
PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, this.camera, robotToCam);
photonPoseEstimator.setMultiTagFallbackStrategy(PoseStrategy.CLOSEST_TO_REFERENCE_POSE);

// SmartDashboard.putNumber("rx", 0);
// SmartDashboard.putNumber("ry", 0);
// SmartDashboard.putNumber("rz", 0);
// SmartDashboard.putNumber("tx", 0);
// SmartDashboard.putNumber("ty", 0);
// SmartDashboard.putNumber("tz", 0);

}

/**
* Update inputs and such.
*/
public void periodic() {
this.io.updateInputs(this.inputs);
Logger.processInputs("PhotonVision/" + inputs.name, inputs);
// if (this.inputs.distCoeffs.length == 0 && Timer.getFPGATimestamp() - resetTimer > 5) {
// resetTimer = Timer.getFPGATimestamp();
// try {
// this.io.uploadSettings(this.io.ip + ":5800",
// new File(Filesystem.getDeployDirectory().getAbsoluteFile(),
// "photon-configs/" + inputs.name + ".zip"));
// } catch (IOException e) {
// e.printStackTrace();
// }
// }
this.camera.periodic();
}

/**
* Gets if photonvision can see a target.
*/
public boolean seesTarget() {
return inputs.result != null && inputs.result.hasTargets();
var result = this.camera.getLatestResult();
return result != null && result.hasTargets();
}

/** A PhotonVision tag solve. */
Expand All @@ -99,8 +77,8 @@ public VisionObservation(int fudicialId, Pose2d robotPose, Matrix<N3, N1> stdDev
* @return an estimated Pose2d based solely on apriltags
*/
public Optional<VisionObservation> getInitialPose() {
var res = inputs.result;
if (res == null || inputs.timeSinceLastHeartbeat > 0.5) {
var res = this.camera.getLatestResult();
if (res == null || Timer.getFPGATimestamp() - res.getTimestampSeconds() > 0.5) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

U should be able to use latency() > 0.5 since u have the same function below

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think latency is actually different from this (calculated pi-side). I'll check, but I agree it should be consistent whatever we do here.

SmartDashboard.putString("reason", "res is null or heartbeat too long");
return Optional.empty();
}
Expand Down Expand Up @@ -129,7 +107,7 @@ public Optional<VisionObservation> getInitialPose() {
}

public double latency() {
var res = inputs.result;
var res = this.camera.getLatestResult();
return Timer.getFPGATimestamp() - res.getTimestampSeconds();
}

Expand All @@ -140,7 +118,7 @@ public double latency() {
* create the estimate
*/
public Optional<EstimatedRobotPose> getEstimatedGlobalPose(Pose2d prevEstimatedRobotPose) {
var res = inputs.result;
var res = this.camera.getLatestResult();

// photonPoseEstimator.setRobotToCameraTransform(new Transform3d(
// new Translation3d(Units.inchesToMeters(SmartDashboard.getNumber("tx", 0)),
Expand Down
109 changes: 0 additions & 109 deletions src/main/java/frc/lib/util/photon/PhotonIO.java

This file was deleted.

Loading
Loading