|
| 1 | +package org.curtinfrc.frc2025.subsystems.drive; |
| 2 | + |
| 3 | +import edu.wpi.first.math.Vector; |
| 4 | +import edu.wpi.first.math.geometry.Pose2d; |
| 5 | +import edu.wpi.first.math.geometry.Rotation2d; |
| 6 | +import edu.wpi.first.math.geometry.Twist2d; |
| 7 | +import edu.wpi.first.math.kinematics.SwerveDriveKinematics; |
| 8 | +import edu.wpi.first.math.kinematics.SwerveModulePosition; |
| 9 | +import edu.wpi.first.math.numbers.N3; |
| 10 | +import edu.wpi.first.wpilibj.RobotController; |
| 11 | +import java.util.LinkedList; |
| 12 | +import java.util.OptionalInt; |
| 13 | + |
| 14 | +public class PoseEstimator { |
| 15 | + private static final double kMaxSampleAge = 0.3; |
| 16 | + |
| 17 | + private final class TimestampedTwist2d extends Twist2d { |
| 18 | + public final double timestamp; |
| 19 | + |
| 20 | + public TimestampedTwist2d(double dx, double dy, double dtheta, double timestamp) { |
| 21 | + super(dx, dy, dtheta); |
| 22 | + this.timestamp = timestamp; |
| 23 | + } |
| 24 | + } |
| 25 | + |
| 26 | + private final LinkedList<TimestampedTwist2d> samples = new LinkedList<>(); |
| 27 | + private Pose2d rootPose = new Pose2d(); |
| 28 | + private final SwerveModulePosition[] prevWheelPositions; |
| 29 | + private final SwerveDriveKinematics kinematics; |
| 30 | + private Rotation2d gyroOffset; |
| 31 | + private Rotation2d prevAngle; |
| 32 | + |
| 33 | + public PoseEstimator( |
| 34 | + SwerveDriveKinematics kinematics, |
| 35 | + SwerveModulePosition[] wheelPositions, |
| 36 | + Rotation2d gyroAngle) { |
| 37 | + this.kinematics = kinematics; |
| 38 | + prevWheelPositions = kinematics.copy(wheelPositions); |
| 39 | + gyroOffset = rootPose.getRotation().minus(gyroAngle); |
| 40 | + prevAngle = rootPose.getRotation(); |
| 41 | + } |
| 42 | + |
| 43 | + public void resetPosition( |
| 44 | + Rotation2d gyroAngle, SwerveModulePosition[] wheelPositions, Pose2d pose) { |
| 45 | + rootPose = pose; |
| 46 | + prevAngle = pose.getRotation(); |
| 47 | + gyroOffset = pose.getRotation().minus(gyroAngle); |
| 48 | + kinematics.copyInto(wheelPositions, prevWheelPositions); |
| 49 | + samples.clear(); |
| 50 | + } |
| 51 | + |
| 52 | + private OptionalInt indexForTimestamp(double timestamp) { |
| 53 | + if (samples.isEmpty()) { |
| 54 | + return OptionalInt.empty(); |
| 55 | + } |
| 56 | + |
| 57 | + if (samples.getFirst().timestamp > timestamp) { |
| 58 | + return OptionalInt.empty(); |
| 59 | + } |
| 60 | + if (samples.getLast().timestamp < timestamp) { |
| 61 | + return OptionalInt.of(samples.size() - 1); |
| 62 | + } |
| 63 | + int low = 0; |
| 64 | + int high = samples.size() - 1; |
| 65 | + while (low <= high) { |
| 66 | + int mid = (low + high) / 2; |
| 67 | + double midTime = samples.get(mid).timestamp; |
| 68 | + if (midTime < timestamp) { |
| 69 | + low = mid + 1; |
| 70 | + } else if (midTime > timestamp) { |
| 71 | + high = mid - 1; |
| 72 | + } else { |
| 73 | + return OptionalInt.of(mid); |
| 74 | + } |
| 75 | + } |
| 76 | + return OptionalInt.of(low - 1); |
| 77 | + } |
| 78 | + |
| 79 | + private Pose2d poseAtIndex(int index) { |
| 80 | + // switching this over to primitive math would be a good idea |
| 81 | + Pose2d pose = rootPose; |
| 82 | + for (int i = 0; i < index; i++) { |
| 83 | + pose = pose.exp(samples.get(i)); |
| 84 | + } |
| 85 | + return pose; |
| 86 | + } |
| 87 | + |
| 88 | + private void pruneToRoot() { |
| 89 | + while (!samples.isEmpty() |
| 90 | + && samples.getFirst().timestamp < RobotController.getTime() - kMaxSampleAge) { |
| 91 | + rootPose = rootPose.exp(samples.removeFirst()); |
| 92 | + } |
| 93 | + } |
| 94 | + |
| 95 | + /** |
| 96 | + * Adds a sample to the estimator |
| 97 | + * |
| 98 | + * @param pose the pose of the robot at the time of the sample |
| 99 | + * @param timestamp the timestamp of the sample |
| 100 | + * @param weight the weight of the sample (0.0 to 1.0) |
| 101 | + */ |
| 102 | + public void addVisionMeasurement(Pose2d pose, double timestamp, Vector<N3> weight) { |
| 103 | + var opt = indexForTimestamp(timestamp); |
| 104 | + if (opt.isEmpty()) { |
| 105 | + // timestamp is before the first sample |
| 106 | + return; |
| 107 | + } |
| 108 | + int index = opt.getAsInt(); |
| 109 | + |
| 110 | + Pose2d lastPose = poseAtIndex(index); |
| 111 | + Twist2d twist = lastPose.log(pose); |
| 112 | + samples.add( |
| 113 | + index, |
| 114 | + new TimestampedTwist2d( |
| 115 | + twist.dx * weight.get(0), |
| 116 | + twist.dy * weight.get(1), |
| 117 | + twist.dtheta * weight.get(2), |
| 118 | + timestamp)); |
| 119 | + pruneToRoot(); |
| 120 | + } |
| 121 | + |
| 122 | + public void updateWithTime( |
| 123 | + SwerveModulePosition[] wheelPositions, |
| 124 | + Rotation2d gyroAngle, |
| 125 | + double timestamp, |
| 126 | + Vector<N3> weight) { |
| 127 | + var angle = gyroAngle.plus(gyroOffset); |
| 128 | + var twist = kinematics.toTwist2d(prevWheelPositions, wheelPositions); |
| 129 | + twist.dtheta = angle.minus(prevAngle).getRadians(); |
| 130 | + |
| 131 | + samples.add( |
| 132 | + new TimestampedTwist2d( |
| 133 | + twist.dx * weight.get(0), |
| 134 | + twist.dy * weight.get(1), |
| 135 | + twist.dtheta * weight.get(2), |
| 136 | + timestamp)); |
| 137 | + |
| 138 | + kinematics.copyInto(wheelPositions, prevWheelPositions); |
| 139 | + prevAngle = angle; |
| 140 | + pruneToRoot(); |
| 141 | + } |
| 142 | + |
| 143 | + public Pose2d getEstimatedPose() { |
| 144 | + return poseAtIndex(samples.size()); |
| 145 | + } |
| 146 | +} |
0 commit comments