Skip to content

Commit

Permalink
Make Vision pose estimation examples use all vision measurements
Browse files Browse the repository at this point in the history
Resolves PhotonVision#1634

Signed-off-by: Jade Turner <[email protected]>
  • Loading branch information
spacey-sooty committed Jan 11, 2025
1 parent 83c124f commit 8bf32d5
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 24 deletions.
1 change: 1 addition & 0 deletions photonlib-cpp-examples/poseest/src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ void Robot::RobotInit() {}
void Robot::RobotPeriodic() {
launcher.periodic();
drivetrain.Periodic();
vision.Periodic();

auto visionEst = vision.GetEstimatedGlobalPose();
if (visionEst.has_value()) {
Expand Down
14 changes: 3 additions & 11 deletions photonlib-java-examples/poseest/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand All @@ -61,16 +61,8 @@ public void robotPeriodic() {
// 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
Expand Down
30 changes: 17 additions & 13 deletions photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,14 @@ public class Vision {
private final PhotonCamera camera;
private final PhotonPoseEstimator photonEstimator;
private Matrix<N3, N1> curStdDevs;
private EstimateConsumer consumer;

// Simulation
private PhotonCameraSim cameraSim;
private VisionSystemSim visionSim;

public Vision() {
public Vision(EstimateConsumer consumer) {
this.consumer = consumer;
camera = new PhotonCamera(kCameraName);

photonEstimator =
Expand Down Expand Up @@ -83,17 +85,7 @@ public 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);
Expand All @@ -109,8 +101,15 @@ public Optional<EstimatedRobotPose> getEstimatedGlobalPose() {
getSimDebugField().getObject("VisionEstimation").setPoses();
});
}

visionEst.ifPresent(
est -> {
// Change our trust in the measurement based on the tags we can see
var estStdDevs = getEstimationStdDevs();

consumer.accept(est.estimatedPose.toPose2d(), est.timestampSeconds, estStdDevs);
});
}
return visionEst;
}

/**
Expand Down Expand Up @@ -188,4 +187,9 @@ public Field2d getSimDebugField() {
if (!Robot.isSimulation()) return null;
return visionSim.getDebugField();
}

@FunctionalInterface
public static interface EstimateConsumer {
public void accept(Pose2d pose, double timestamp, Matrix<N3, N1> estimationStdDevs);
}
}

0 comments on commit 8bf32d5

Please sign in to comment.