001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.math.estimator; 006 007import edu.wpi.first.math.MathSharedStore; 008import edu.wpi.first.math.MathUsageId; 009import edu.wpi.first.math.MathUtil; 010import edu.wpi.first.math.Matrix; 011import edu.wpi.first.math.geometry.Pose2d; 012import edu.wpi.first.math.geometry.Rotation2d; 013import edu.wpi.first.math.geometry.Transform2d; 014import edu.wpi.first.math.geometry.Translation2d; 015import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer; 016import edu.wpi.first.math.kinematics.Kinematics; 017import edu.wpi.first.math.kinematics.Odometry; 018import edu.wpi.first.math.numbers.N1; 019import edu.wpi.first.math.numbers.N3; 020import java.util.NavigableMap; 021import java.util.Optional; 022import java.util.TreeMap; 023 024/** 025 * This class wraps {@link Odometry} to fuse latency-compensated vision measurements with encoder 026 * measurements. Robot code should not use this directly- Instead, use the particular type for your 027 * drivetrain (e.g., {@link DifferentialDrivePoseEstimator}). It is intended to be a drop-in 028 * replacement for {@link Odometry}; in fact, if you never call {@link 029 * PoseEstimator#addVisionMeasurement} and only call {@link PoseEstimator#update} then this will 030 * behave exactly the same as Odometry. 031 * 032 * <p>{@link PoseEstimator#update} should be called every robot loop. 033 * 034 * <p>{@link PoseEstimator#addVisionMeasurement} can be called as infrequently as you want; if you 035 * never call it then this class will behave exactly like regular encoder odometry. 036 * 037 * @param <T> Wheel positions type. 038 */ 039public class PoseEstimator<T> { 040 private final Odometry<T> m_odometry; 041 042 // Diagonal of process noise covariance matrix Q 043 private final double[] m_q = new double[] {0.0, 0.0, 0.0}; 044 045 // Diagonal of Kalman gain matrix K 046 private final double[] m_vision_k = new double[] {0.0, 0.0, 0.0}; 047 048 private static final double kBufferDuration = 1.5; 049 // Maps timestamps to odometry-only pose estimates 050 private final TimeInterpolatableBuffer<Pose2d> m_odometryPoseBuffer = 051 TimeInterpolatableBuffer.createBuffer(kBufferDuration); 052 // Maps timestamps to vision updates 053 // Always contains one entry before the oldest entry in m_odometryPoseBuffer, unless there have 054 // been no vision measurements after the last reset. May contain one entry while 055 // m_odometryPoseBuffer is empty to correct for translation/rotation after a call to 056 // ResetRotation/ResetTranslation. 057 private final NavigableMap<Double, VisionUpdate> m_visionUpdates = new TreeMap<>(); 058 059 private Pose2d m_poseEstimate; 060 061 /** 062 * Constructs a PoseEstimator. 063 * 064 * @param kinematics A correctly-configured kinematics object for your drivetrain. 065 * @param odometry A correctly-configured odometry object for your drivetrain. 066 * @param stateStdDevs Standard deviations of the pose estimate (x position in meters, y position 067 * in meters, and heading in radians). Increase these numbers to trust your state estimate 068 * less. 069 * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position 070 * in meters, y position in meters, and heading in radians). Increase these numbers to trust 071 * the vision pose measurement less. 072 */ 073 @SuppressWarnings("PMD.UnusedFormalParameter") 074 public PoseEstimator( 075 Kinematics<?, T> kinematics, 076 Odometry<T> odometry, 077 Matrix<N3, N1> stateStdDevs, 078 Matrix<N3, N1> visionMeasurementStdDevs) { 079 m_odometry = odometry; 080 081 m_poseEstimate = m_odometry.getPoseMeters(); 082 083 for (int i = 0; i < 3; ++i) { 084 m_q[i] = stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0); 085 } 086 setVisionMeasurementStdDevs(visionMeasurementStdDevs); 087 MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_PoseEstimator, 1); 088 } 089 090 /** 091 * Sets the pose estimator's trust of global measurements. This might be used to change trust in 092 * vision measurements after the autonomous period, or to change trust as distance to a vision 093 * target increases. 094 * 095 * @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these 096 * numbers to trust global measurements from vision less. This matrix is in the form [x, y, 097 * theta]ᵀ, with units in meters and radians. 098 */ 099 public final void setVisionMeasurementStdDevs(Matrix<N3, N1> visionMeasurementStdDevs) { 100 // Diagonal of measurement noise covariance matrix R 101 var r = new double[3]; 102 for (int i = 0; i < 3; ++i) { 103 r[i] = visionMeasurementStdDevs.get(i, 0) * visionMeasurementStdDevs.get(i, 0); 104 } 105 106 // Solve for closed form Kalman gain for continuous Kalman filter with A = 0 107 // and C = I. See wpimath/algorithms.md. 108 for (int row = 0; row < 3; ++row) { 109 if (m_q[row] == 0.0) { 110 m_vision_k[row] = 0.0; 111 } else { 112 m_vision_k[row] = m_q[row] / (m_q[row] + Math.sqrt(m_q[row] * r[row])); 113 } 114 } 115 } 116 117 /** 118 * Resets the robot's position on the field. 119 * 120 * <p>The gyroscope angle does not need to be reset here on the user's robot code. The library 121 * automatically takes care of offsetting the gyro angle. 122 * 123 * @param gyroAngle The angle reported by the gyroscope. 124 * @param wheelPositions The current encoder readings. 125 * @param poseMeters The position on the field that your robot is at. 126 */ 127 public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMeters) { 128 // Reset state estimate and error covariance 129 m_odometry.resetPosition(gyroAngle, wheelPositions, poseMeters); 130 m_odometryPoseBuffer.clear(); 131 m_visionUpdates.clear(); 132 m_poseEstimate = m_odometry.getPoseMeters(); 133 } 134 135 /** 136 * Resets the robot's pose. 137 * 138 * @param pose The pose to reset to. 139 */ 140 public void resetPose(Pose2d pose) { 141 m_odometry.resetPose(pose); 142 m_odometryPoseBuffer.clear(); 143 m_visionUpdates.clear(); 144 m_poseEstimate = m_odometry.getPoseMeters(); 145 } 146 147 /** 148 * Resets the robot's translation. 149 * 150 * @param translation The pose to translation to. 151 */ 152 public void resetTranslation(Translation2d translation) { 153 m_odometry.resetTranslation(translation); 154 155 final var latestVisionUpdate = m_visionUpdates.lastEntry(); 156 m_odometryPoseBuffer.clear(); 157 m_visionUpdates.clear(); 158 159 if (latestVisionUpdate != null) { 160 // apply vision compensation to the pose rotation 161 final var visionUpdate = 162 new VisionUpdate( 163 new Pose2d(translation, latestVisionUpdate.getValue().visionPose.getRotation()), 164 new Pose2d(translation, latestVisionUpdate.getValue().odometryPose.getRotation())); 165 m_visionUpdates.put(latestVisionUpdate.getKey(), visionUpdate); 166 m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); 167 } else { 168 m_poseEstimate = m_odometry.getPoseMeters(); 169 } 170 } 171 172 /** 173 * Resets the robot's rotation. 174 * 175 * @param rotation The rotation to reset to. 176 */ 177 public void resetRotation(Rotation2d rotation) { 178 m_odometry.resetRotation(rotation); 179 180 final var latestVisionUpdate = m_visionUpdates.lastEntry(); 181 m_odometryPoseBuffer.clear(); 182 m_visionUpdates.clear(); 183 184 if (latestVisionUpdate != null) { 185 // apply vision compensation to the pose translation 186 final var visionUpdate = 187 new VisionUpdate( 188 new Pose2d(latestVisionUpdate.getValue().visionPose.getTranslation(), rotation), 189 new Pose2d(latestVisionUpdate.getValue().odometryPose.getTranslation(), rotation)); 190 m_visionUpdates.put(latestVisionUpdate.getKey(), visionUpdate); 191 m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); 192 } else { 193 m_poseEstimate = m_odometry.getPoseMeters(); 194 } 195 } 196 197 /** 198 * Gets the estimated robot pose. 199 * 200 * @return The estimated robot pose in meters. 201 */ 202 public Pose2d getEstimatedPosition() { 203 return m_poseEstimate; 204 } 205 206 /** 207 * Return the pose at a given timestamp, if the buffer is not empty. 208 * 209 * @param timestampSeconds The pose's timestamp in seconds. 210 * @return The pose at the given timestamp (or Optional.empty() if the buffer is empty). 211 */ 212 public Optional<Pose2d> sampleAt(double timestampSeconds) { 213 // Step 0: If there are no odometry updates to sample, skip. 214 if (m_odometryPoseBuffer.getInternalBuffer().isEmpty()) { 215 return Optional.empty(); 216 } 217 218 // Step 1: Make sure timestamp matches the sample from the odometry pose buffer. (When sampling, 219 // the buffer will always use a timestamp between the first and last timestamps) 220 double oldestOdometryTimestamp = m_odometryPoseBuffer.getInternalBuffer().firstKey(); 221 double newestOdometryTimestamp = m_odometryPoseBuffer.getInternalBuffer().lastKey(); 222 timestampSeconds = 223 MathUtil.clamp(timestampSeconds, oldestOdometryTimestamp, newestOdometryTimestamp); 224 225 // Step 2: If there are no applicable vision updates, use the odometry-only information. 226 if (m_visionUpdates.isEmpty() || timestampSeconds < m_visionUpdates.firstKey()) { 227 return m_odometryPoseBuffer.getSample(timestampSeconds); 228 } 229 230 // Step 3: Get the latest vision update from before or at the timestamp to sample at. 231 double floorTimestamp = m_visionUpdates.floorKey(timestampSeconds); 232 var visionUpdate = m_visionUpdates.get(floorTimestamp); 233 234 // Step 4: Get the pose measured by odometry at the time of the sample. 235 var odometryEstimate = m_odometryPoseBuffer.getSample(timestampSeconds); 236 237 // Step 5: Apply the vision compensation to the odometry pose. 238 return odometryEstimate.map(odometryPose -> visionUpdate.compensate(odometryPose)); 239 } 240 241 /** Removes stale vision updates that won't affect sampling. */ 242 private void cleanUpVisionUpdates() { 243 // Step 0: If there are no odometry samples, skip. 244 if (m_odometryPoseBuffer.getInternalBuffer().isEmpty()) { 245 return; 246 } 247 248 // Step 1: Find the oldest timestamp that needs a vision update. 249 double oldestOdometryTimestamp = m_odometryPoseBuffer.getInternalBuffer().firstKey(); 250 251 // Step 2: If there are no vision updates before that timestamp, skip. 252 if (m_visionUpdates.isEmpty() || oldestOdometryTimestamp < m_visionUpdates.firstKey()) { 253 return; 254 } 255 256 // Step 3: Find the newest vision update timestamp before or at the oldest timestamp. 257 double newestNeededVisionUpdateTimestamp = m_visionUpdates.floorKey(oldestOdometryTimestamp); 258 259 // Step 4: Remove all entries strictly before the newest timestamp we need. 260 m_visionUpdates.headMap(newestNeededVisionUpdateTimestamp, false).clear(); 261 } 262 263 /** 264 * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate 265 * while still accounting for measurement noise. 266 * 267 * <p>This method can be called as infrequently as you want, as long as you are calling {@link 268 * PoseEstimator#update} every loop. 269 * 270 * <p>To promote stability of the pose estimate and make it robust to bad vision data, we 271 * recommend only adding vision measurements that are already within one meter or so of the 272 * current pose estimate. 273 * 274 * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera. 275 * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you 276 * don't use your own time source by calling {@link 277 * PoseEstimator#updateWithTime(double,Rotation2d,Object)} then you must use a timestamp with 278 * an epoch since FPGA startup (i.e., the epoch of this timestamp is the same epoch as {@link 279 * edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}.) This means that you should use {@link 280 * edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source or sync the epochs. 281 */ 282 public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) { 283 // Step 0: If this measurement is old enough to be outside the pose buffer's timespan, skip. 284 if (m_odometryPoseBuffer.getInternalBuffer().isEmpty() 285 || m_odometryPoseBuffer.getInternalBuffer().lastKey() - kBufferDuration 286 > timestampSeconds) { 287 return; 288 } 289 290 // Step 1: Clean up any old entries 291 cleanUpVisionUpdates(); 292 293 // Step 2: Get the pose measured by odometry at the moment the vision measurement was made. 294 var odometrySample = m_odometryPoseBuffer.getSample(timestampSeconds); 295 296 if (odometrySample.isEmpty()) { 297 return; 298 } 299 300 // Step 3: Get the vision-compensated pose estimate at the moment the vision measurement was 301 // made. 302 var visionSample = sampleAt(timestampSeconds); 303 304 if (visionSample.isEmpty()) { 305 return; 306 } 307 308 // Step 4: Measure the transform between the old pose estimate and the vision pose. 309 var transform = visionRobotPoseMeters.minus(visionSample.get()); 310 311 // Step 5: We should not trust the transform entirely, so instead we scale this transform by a 312 // Kalman gain matrix representing how much we trust vision measurements compared to our current 313 // pose. Then, we convert the result back to a Transform2d. 314 var scaledTransform = 315 new Transform2d( 316 m_vision_k[0] * transform.getX(), 317 m_vision_k[1] * transform.getY(), 318 Rotation2d.fromRadians(m_vision_k[2] * transform.getRotation().getRadians())); 319 320 // Step 6: Calculate and record the vision update. 321 var visionUpdate = 322 new VisionUpdate(visionSample.get().plus(scaledTransform), odometrySample.get()); 323 m_visionUpdates.put(timestampSeconds, visionUpdate); 324 325 // Step 7: Remove later vision measurements. (Matches previous behavior) 326 m_visionUpdates.tailMap(timestampSeconds, false).entrySet().clear(); 327 328 // Step 8: Update latest pose estimate. Since we cleared all updates after this vision update, 329 // it's guaranteed to be the latest vision update. 330 m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); 331 } 332 333 /** 334 * Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate 335 * while still accounting for measurement noise. 336 * 337 * <p>This method can be called as infrequently as you want, as long as you are calling {@link 338 * PoseEstimator#update} every loop. 339 * 340 * <p>To promote stability of the pose estimate and make it robust to bad vision data, we 341 * recommend only adding vision measurements that are already within one meter or so of the 342 * current pose estimate. 343 * 344 * <p>Note that the vision measurement standard deviations passed into this method will continue 345 * to apply to future measurements until a subsequent call to {@link 346 * PoseEstimator#setVisionMeasurementStdDevs(Matrix)} or this method. 347 * 348 * @param visionRobotPoseMeters The pose of the robot as measured by the vision camera. 349 * @param timestampSeconds The timestamp of the vision measurement in seconds. Note that if you 350 * don't use your own time source by calling {@link #updateWithTime}, then you must use a 351 * timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is the same 352 * epoch as {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()}). This means that you 353 * should use {@link edu.wpi.first.wpilibj.Timer#getFPGATimestamp()} as your time source in 354 * this case. 355 * @param visionMeasurementStdDevs Standard deviations of the vision pose measurement (x position 356 * in meters, y position in meters, and heading in radians). Increase these numbers to trust 357 * the vision pose measurement less. 358 */ 359 public void addVisionMeasurement( 360 Pose2d visionRobotPoseMeters, 361 double timestampSeconds, 362 Matrix<N3, N1> visionMeasurementStdDevs) { 363 setVisionMeasurementStdDevs(visionMeasurementStdDevs); 364 addVisionMeasurement(visionRobotPoseMeters, timestampSeconds); 365 } 366 367 /** 368 * Updates the pose estimator with wheel encoder and gyro information. This should be called every 369 * loop. 370 * 371 * @param gyroAngle The current gyro angle. 372 * @param wheelPositions The current encoder readings. 373 * @return The estimated pose of the robot in meters. 374 */ 375 public Pose2d update(Rotation2d gyroAngle, T wheelPositions) { 376 return updateWithTime(MathSharedStore.getTimestamp(), gyroAngle, wheelPositions); 377 } 378 379 /** 380 * Updates the pose estimator with wheel encoder and gyro information. This should be called every 381 * loop. 382 * 383 * @param currentTimeSeconds Time at which this method was called, in seconds. 384 * @param gyroAngle The current gyro angle. 385 * @param wheelPositions The current encoder readings. 386 * @return The estimated pose of the robot in meters. 387 */ 388 public Pose2d updateWithTime(double currentTimeSeconds, Rotation2d gyroAngle, T wheelPositions) { 389 var odometryEstimate = m_odometry.update(gyroAngle, wheelPositions); 390 391 m_odometryPoseBuffer.addSample(currentTimeSeconds, odometryEstimate); 392 393 if (m_visionUpdates.isEmpty()) { 394 m_poseEstimate = odometryEstimate; 395 } else { 396 var visionUpdate = m_visionUpdates.get(m_visionUpdates.lastKey()); 397 m_poseEstimate = visionUpdate.compensate(odometryEstimate); 398 } 399 400 return getEstimatedPosition(); 401 } 402 403 /** 404 * Represents a vision update record. The record contains the vision-compensated pose estimate as 405 * well as the corresponding odometry pose estimate. 406 */ 407 private static final class VisionUpdate { 408 // The vision-compensated pose estimate. 409 private final Pose2d visionPose; 410 411 // The pose estimated based solely on odometry. 412 private final Pose2d odometryPose; 413 414 /** 415 * Constructs a vision update record with the specified parameters. 416 * 417 * @param visionPose The vision-compensated pose estimate. 418 * @param odometryPose The pose estimate based solely on odometry. 419 */ 420 private VisionUpdate(Pose2d visionPose, Pose2d odometryPose) { 421 this.visionPose = visionPose; 422 this.odometryPose = odometryPose; 423 } 424 425 /** 426 * Returns the vision-compensated version of the pose. Specifically, changes the pose from being 427 * relative to this record's odometry pose to being relative to this record's vision pose. 428 * 429 * @param pose The pose to compensate. 430 * @return The compensated pose. 431 */ 432 public Pose2d compensate(Pose2d pose) { 433 var delta = pose.minus(this.odometryPose); 434 return this.visionPose.plus(delta); 435 } 436 } 437}