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