diff --git a/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/DifferentialDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/DifferentialDrivePoseEstimator.java index eabb67ee38..66873dec41 100644 --- a/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/DifferentialDrivePoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/DifferentialDrivePoseEstimator.java @@ -256,6 +256,36 @@ public class DifferentialDrivePoseEstimator { timestampSeconds); } + /** + * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose + * estimate while still accounting for measurement noise. + * + *

This method can be called as infrequently as you want, as long as you are calling {@link + * DifferentialDrivePoseEstimator#update} every loop. + * + *

Note that the vision measurement standard deviations passed into this method will continue + * to apply to future measurements until a subsequent call to {@link + * DifferentialDrivePoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method. + * + * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera. + * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you + * don't use your own time source by calling {@link + * DifferentialDrivePoseEstimator#updateWithTime} then you must use a timestamp with an epoch + * since FPGA startup (i.e. the epoch of this timestamp is the same epoch as + * Timer.getFPGATimestamp.) This means that you should use Timer.getFPGATimestamp as your time + * source in this case. + * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these + * numbers to trust global measurements from vision less. This matrix is in the form [x, y, + * theta]^T, with units in meters and radians. + */ + public void addVisionMeasurement( + Pose2d visionRobotPoseMeters, + double timestampSeconds, + Matrix visionMeasurementStdDevs) { + setVisionMeasurementStdDevs(visionMeasurementStdDevs); + addVisionMeasurement(visionRobotPoseMeters, timestampSeconds); + } + /** * Updates the the Unscented Kalman Filter using only wheel encoder information. Note that this * should be called every loop. diff --git a/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/MecanumDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/MecanumDrivePoseEstimator.java index 6ff5264449..afca17dae9 100644 --- a/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/MecanumDrivePoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/MecanumDrivePoseEstimator.java @@ -220,6 +220,35 @@ public class MecanumDrivePoseEstimator { timestampSeconds); } + /** + * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose + * estimate while still accounting for measurement noise. + * + *

This method can be called as infrequently as you want, as long as you are calling {@link + * MecanumDrivePoseEstimator#update} every loop. + * + *

Note that the vision measurement standard deviations passed into this method will continue + * to apply to future measurements until a subsequent call to {@link + * MecanumDrivePoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method. + * + * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera. + * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you + * don't use your own time source by calling {@link MecanumDrivePoseEstimator#updateWithTime} + * then you must use a timestamp with an epoch since FPGA startup (i.e. the epoch of this + * timestamp is the same epoch as Timer.getFPGATimestamp.) This means that you should use + * Timer.getFPGATimestamp as your time source in this case. + * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these + * numbers to trust global measurements from vision less. This matrix is in the form [x, y, + * theta]^T, with units in meters and radians. + */ + public void addVisionMeasurement( + Pose2d visionRobotPoseMeters, + double timestampSeconds, + Matrix visionMeasurementStdDevs) { + setVisionMeasurementStdDevs(visionMeasurementStdDevs); + addVisionMeasurement(visionRobotPoseMeters, timestampSeconds); + } + /** * Updates the the Unscented Kalman Filter using only wheel encoder information. This should be * called every loop, and the correct loop period must be passed into the constructor of this diff --git a/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/SwerveDrivePoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/SwerveDrivePoseEstimator.java index 34f7376ab6..958e8357e7 100644 --- a/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/SwerveDrivePoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/wpilibj/estimator/SwerveDrivePoseEstimator.java @@ -220,6 +220,35 @@ public class SwerveDrivePoseEstimator { timestampSeconds); } + /** + * Add a vision measurement to the Unscented Kalman Filter. This will correct the odometry pose + * estimate while still accounting for measurement noise. + * + *

This method can be called as infrequently as you want, as long as you are calling {@link + * SwerveDrivePoseEstimator#update} every loop. + * + *

Note that the vision measurement standard deviations passed into this method will continue + * to apply to future measurements until a subsequent call to {@link + * SwerveDrivePoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method. + * + * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera. + * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you + * don't use your own time source by calling {@link SwerveDrivePoseEstimator#updateWithTime} + * then you must use a timestamp with an epoch since FPGA startup (i.e. the epoch of this + * timestamp is the same epoch as Timer.getFPGATimestamp.) This means that you should use + * Timer.getFPGATimestamp as your time source in this case. + * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these + * numbers to trust global measurements from vision less. This matrix is in the form [x, y, + * theta]^T, with units in meters and radians. + */ + public void addVisionMeasurement( + Pose2d visionRobotPoseMeters, + double timestampSeconds, + Matrix visionMeasurementStdDevs) { + setVisionMeasurementStdDevs(visionMeasurementStdDevs); + addVisionMeasurement(visionRobotPoseMeters, timestampSeconds); + } + /** * Updates the the Unscented Kalman Filter using only wheel encoder information. This should be * called every loop, and the correct loop period must be passed into the constructor of this diff --git a/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h index 1d366a9a2a..9fea0b6a15 100644 --- a/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/DifferentialDrivePoseEstimator.h @@ -135,6 +135,44 @@ class DifferentialDrivePoseEstimator { void AddVisionMeasurement(const Pose2d& visionRobotPose, units::second_t timestamp); + /** + * Adds a vision measurement to the Unscented Kalman Filter. This will correct + * the odometry pose estimate while still accounting for measurement noise. + * + * This method can be called as infrequently as you want, as long as you are + * calling Update() every loop. + * + * Note that the vision measurement standard deviations passed into this + * method will continue to apply to future measurements until a subsequent + * call to SetVisionMeasurementStdDevs() or this method. + * + * @param visionRobotPose The pose of the robot as measured by the + * vision camera. + * @param timestamp The timestamp of the vision measurement in + * seconds. Note that if you don't use your + * own time source by calling + * UpdateWithTime(), then you must use a + * timestamp with an epoch since FPGA startup + * (i.e. the epoch of this timestamp is the + * same epoch as + * frc2::Timer::GetFPGATimestamp(). This means + * that you should use + * frc2::Timer::GetFPGATimestamp() as your + * time source in this case. + * @param visionMeasurementStdDevs Standard deviations of the vision + * measurements. Increase these numbers to + * trust global measurements from vision + * less. This matrix is in the form + * [x, y, theta]^T, with units in meters and + * radians. + */ + void AddVisionMeasurement( + const Pose2d& visionRobotPose, units::second_t timestamp, + const wpi::array& visionMeasurementStdDevs) { + SetVisionMeasurementStdDevs(visionMeasurementStdDevs); + AddVisionMeasurement(visionRobotPose, timestamp); + } + /** * Updates the Unscented Kalman Filter using only wheel encoder information. * Note that this should be called every loop iteration. diff --git a/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h index c7fb8590ba..8e43b01fde 100644 --- a/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/MecanumDrivePoseEstimator.h @@ -135,6 +135,44 @@ class MecanumDrivePoseEstimator { void AddVisionMeasurement(const Pose2d& visionRobotPose, units::second_t timestamp); + /** + * Adds a vision measurement to the Unscented Kalman Filter. This will correct + * the odometry pose estimate while still accounting for measurement noise. + * + * This method can be called as infrequently as you want, as long as you are + * calling Update() every loop. + * + * Note that the vision measurement standard deviations passed into this + * method will continue to apply to future measurements until a subsequent + * call to SetVisionMeasurementStdDevs() or this method. + * + * @param visionRobotPose The pose of the robot as measured by the + * vision camera. + * @param timestamp The timestamp of the vision measurement in + * seconds. Note that if you don't use your + * own time source by calling + * UpdateWithTime(), then you must use a + * timestamp with an epoch since FPGA startup + * (i.e. the epoch of this timestamp is the + * same epoch as + * frc2::Timer::GetFPGATimestamp(). This means + * that you should use + * frc2::Timer::GetFPGATimestamp() as your + * time source in this case. + * @param visionMeasurementStdDevs Standard deviations of the vision + * measurements. Increase these numbers to + * trust global measurements from vision + * less. This matrix is in the form + * [x, y, theta]^T, with units in meters and + * radians. + */ + void AddVisionMeasurement( + const Pose2d& visionRobotPose, units::second_t timestamp, + const wpi::array& visionMeasurementStdDevs) { + SetVisionMeasurementStdDevs(visionMeasurementStdDevs); + AddVisionMeasurement(visionRobotPose, timestamp); + } + /** * Updates the the Unscented Kalman Filter using only wheel encoder * information. This should be called every loop, and the correct loop period diff --git a/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h index 74e7747ccb..f751470c32 100644 --- a/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseEstimator.h @@ -189,6 +189,44 @@ class SwerveDrivePoseEstimator { m_visionCorrect, timestamp); } + /** + * Adds a vision measurement to the Unscented Kalman Filter. This will correct + * the odometry pose estimate while still accounting for measurement noise. + * + * This method can be called as infrequently as you want, as long as you are + * calling Update() every loop. + * + * Note that the vision measurement standard deviations passed into this + * method will continue to apply to future measurements until a subsequent + * call to SetVisionMeasurementStdDevs() or this method. + * + * @param visionRobotPose The pose of the robot as measured by the + * vision camera. + * @param timestamp The timestamp of the vision measurement in + * seconds. Note that if you don't use your + * own time source by calling + * UpdateWithTime(), then you must use a + * timestamp with an epoch since FPGA startup + * (i.e. the epoch of this timestamp is the + * same epoch as + * frc2::Timer::GetFPGATimestamp(). This means + * that you should use + * frc2::Timer::GetFPGATimestamp() as your + * time source in this case. + * @param visionMeasurementStdDevs Standard deviations of the vision + * measurements. Increase these numbers to + * trust global measurements from vision + * less. This matrix is in the form + * [x, y, theta]^T, with units in meters and + * radians. + */ + void AddVisionMeasurement( + const Pose2d& visionRobotPose, units::second_t timestamp, + const wpi::array& visionMeasurementStdDevs) { + SetVisionMeasurementStdDevs(visionMeasurementStdDevs); + AddVisionMeasurement(visionRobotPose, timestamp); + } + /** * Updates the the Unscented Kalman Filter using only wheel encoder * information. This should be called every loop, and the correct loop period