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

Warn when getBestCameraToTarget returns 0, 0, 0 #1334

Merged
merged 6 commits into from
Jun 1, 2024
Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import edu.wpi.first.apriltag.AprilTagDetection;
import edu.wpi.first.apriltag.AprilTagPoseEstimate;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.wpilibj.DriverStation;
import java.util.ArrayList;
import java.util.HashMap;
import java.util.List;
Expand Down Expand Up @@ -364,6 +365,9 @@ public boolean hasSubContours() {
}

public Transform3d getBestCameraToTarget3d() {
if (m_bestCameraToTarget3d.equals(new Transform3d())) {
DriverStation.reportWarning("3d mode is not enabled.", false);
}
return m_bestCameraToTarget3d;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
#include <utility>
#include <vector>

#include <frc/Errors.h>
#include <frc/geometry/Transform3d.h>
#include <wpi/SmallVector.h>

Expand Down Expand Up @@ -138,7 +139,12 @@ class PhotonTrackedTarget {
* reprojection error is the ambiguity, which is between 0 and 1.
* @return The pose of the target relative to the robot.
*/
frc::Transform3d GetBestCameraToTarget() const { return bestCameraToTarget; }
frc::Transform3d GetBestCameraToTarget() const {
if (bestCameraToTarget == frc::Transform3d()) {
spacey-sooty marked this conversation as resolved.
Show resolved Hide resolved
FRC_ReportError(frc::warn::Warning, "3d mode is not enabled");
}
return bestCameraToTarget;
}

/**
* Get the transform that maps camera space (X = forward, Y = left, Z = up) to
Expand Down
Loading