mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
Make Vision pose estimation examples use all vision measurements (#1706)
Resolves https://github.com/PhotonVision/photonvision/issues/1634 --------- Signed-off-by: Jade Turner <spacey-sooty@proton.me> Co-authored-by: Sam Freund <techguy763@gmail.com>
This commit is contained in:
@@ -34,15 +34,7 @@ void Robot::RobotInit() {}
|
||||
void Robot::RobotPeriodic() {
|
||||
launcher.periodic();
|
||||
drivetrain.Periodic();
|
||||
|
||||
auto visionEst = vision.GetEstimatedGlobalPose();
|
||||
if (visionEst.has_value()) {
|
||||
auto est = visionEst.value();
|
||||
auto estPose = est.estimatedPose.ToPose2d();
|
||||
auto estStdDevs = vision.GetEstimationStdDevs(estPose);
|
||||
drivetrain.AddVisionMeasurement(est.estimatedPose.ToPose2d(), est.timestamp,
|
||||
estStdDevs);
|
||||
}
|
||||
vision.Periodic();
|
||||
|
||||
drivetrain.Log();
|
||||
}
|
||||
|
||||
@@ -51,7 +51,10 @@ class Robot : public frc::TimedRobot {
|
||||
|
||||
private:
|
||||
SwerveDrive drivetrain{};
|
||||
Vision vision{};
|
||||
Vision vision{[=, this](frc::Pose2d pose, units::second_t timestamp,
|
||||
Eigen::Matrix<double, 3, 1> stddevs) {
|
||||
drivetrain.AddVisionMeasurement(pose, timestamp, stddevs);
|
||||
}};
|
||||
GamepieceLauncher launcher{};
|
||||
frc::XboxController controller{0};
|
||||
};
|
||||
|
||||
@@ -31,6 +31,7 @@
|
||||
#include <photon/simulation/VisionTargetSim.h>
|
||||
#include <photon/targeting/PhotonPipelineResult.h>
|
||||
|
||||
#include <functional>
|
||||
#include <limits>
|
||||
#include <memory>
|
||||
|
||||
@@ -41,7 +42,14 @@
|
||||
|
||||
class Vision {
|
||||
public:
|
||||
Vision() {
|
||||
/**
|
||||
* @param estConsumer Lamba that will accept a pose estimate and pass it to
|
||||
* your desired SwerveDrivePoseEstimator.
|
||||
*/
|
||||
Vision(std::function<void(frc::Pose2d, units::second_t,
|
||||
Eigen::Matrix<double, 3, 1>)>
|
||||
estConsumer)
|
||||
: estConsumer{estConsumer} {
|
||||
photonEstimator.SetMultiTagFallbackStrategy(
|
||||
photon::PoseStrategy::LOWEST_AMBIGUITY);
|
||||
|
||||
@@ -68,9 +76,7 @@ class Vision {
|
||||
|
||||
photon::PhotonPipelineResult GetLatestResult() { return m_latestResult; }
|
||||
|
||||
std::optional<photon::EstimatedRobotPose> GetEstimatedGlobalPose() {
|
||||
std::optional<photon::EstimatedRobotPose> visionEst;
|
||||
|
||||
void Periodic() {
|
||||
// Run each new pipeline result through our pose estimator
|
||||
for (const auto& result : camera.GetAllUnreadResults()) {
|
||||
// cache result and update pose estimator
|
||||
@@ -87,9 +93,12 @@ class Vision {
|
||||
GetSimDebugField().GetObject("VisionEstimation")->SetPoses({});
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return visionEst;
|
||||
if (visionEst) {
|
||||
estConsumer(visionEst->estimatedPose.ToPose2d(), visionEst->timestamp,
|
||||
GetEstimationStdDevs(visionEst->estimatedPose.ToPose2d()));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Eigen::Matrix<double, 3, 1> GetEstimationStdDevs(frc::Pose2d estimatedPose) {
|
||||
@@ -149,4 +158,6 @@ class Vision {
|
||||
|
||||
// The most recent result, cached for calculating std devs
|
||||
photon::PhotonPipelineResult m_latestResult;
|
||||
std::function<void(frc::Pose2d, units::second_t, Eigen::Matrix<double, 3, 1>)>
|
||||
estConsumer;
|
||||
};
|
||||
|
||||
@@ -46,7 +46,7 @@ public class Robot extends TimedRobot {
|
||||
@Override
|
||||
public void robotInit() {
|
||||
drivetrain = new SwerveDrive();
|
||||
vision = new Vision();
|
||||
vision = new Vision(drivetrain::addVisionMeasurement);
|
||||
|
||||
controller = new XboxController(0);
|
||||
|
||||
@@ -61,16 +61,8 @@ public class Robot extends TimedRobot {
|
||||
// Update drivetrain subsystem
|
||||
drivetrain.periodic();
|
||||
|
||||
// Correct pose estimate with vision measurements
|
||||
var visionEst = vision.getEstimatedGlobalPose();
|
||||
visionEst.ifPresent(
|
||||
est -> {
|
||||
// Change our trust in the measurement based on the tags we can see
|
||||
var estStdDevs = vision.getEstimationStdDevs();
|
||||
|
||||
drivetrain.addVisionMeasurement(
|
||||
est.estimatedPose.toPose2d(), est.timestampSeconds, estStdDevs);
|
||||
});
|
||||
// Update vision
|
||||
vision.periodic();
|
||||
|
||||
// Test/Example only!
|
||||
// Apply an offset to pose estimator to test vision correction
|
||||
|
||||
@@ -48,12 +48,18 @@ public class Vision {
|
||||
private final PhotonCamera camera;
|
||||
private final PhotonPoseEstimator photonEstimator;
|
||||
private Matrix<N3, N1> curStdDevs;
|
||||
private final EstimateConsumer estConsumer;
|
||||
|
||||
// Simulation
|
||||
private PhotonCameraSim cameraSim;
|
||||
private VisionSystemSim visionSim;
|
||||
|
||||
public Vision() {
|
||||
/**
|
||||
* @param estConsumer Lamba that will accept a pose estimate and pass it to your desired {@link
|
||||
* edu.wpi.first.math.estimator.SwerveDrivePoseEstimator}
|
||||
*/
|
||||
public Vision(EstimateConsumer estConsumer) {
|
||||
this.estConsumer = estConsumer;
|
||||
camera = new PhotonCamera(kCameraName);
|
||||
|
||||
photonEstimator =
|
||||
@@ -83,17 +89,7 @@ public class Vision {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* The latest estimated robot pose on the field from vision data. This may be empty. This should
|
||||
* only be called once per loop.
|
||||
*
|
||||
* <p>Also includes updates for the standard deviations, which can (optionally) be retrieved with
|
||||
* {@link getEstimationStdDevs}
|
||||
*
|
||||
* @return An {@link EstimatedRobotPose} with an estimated pose, estimate timestamp, and targets
|
||||
* used for estimation.
|
||||
*/
|
||||
public Optional<EstimatedRobotPose> getEstimatedGlobalPose() {
|
||||
public void periodic() {
|
||||
Optional<EstimatedRobotPose> visionEst = Optional.empty();
|
||||
for (var change : camera.getAllUnreadResults()) {
|
||||
visionEst = photonEstimator.update(change);
|
||||
@@ -109,8 +105,15 @@ public class Vision {
|
||||
getSimDebugField().getObject("VisionEstimation").setPoses();
|
||||
});
|
||||
}
|
||||
|
||||
visionEst.ifPresent(
|
||||
est -> {
|
||||
// Change our trust in the measurement based on the tags we can see
|
||||
var estStdDevs = getEstimationStdDevs();
|
||||
|
||||
estConsumer.accept(est.estimatedPose.toPose2d(), est.timestampSeconds, estStdDevs);
|
||||
});
|
||||
}
|
||||
return visionEst;
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -188,4 +191,9 @@ public class Vision {
|
||||
if (!Robot.isSimulation()) return null;
|
||||
return visionSim.getDebugField();
|
||||
}
|
||||
|
||||
@FunctionalInterface
|
||||
public static interface EstimateConsumer {
|
||||
public void accept(Pose2d pose, double timestamp, Matrix<N3, N1> estimationStdDevs);
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user