Skip to content
This repository was archived by the owner on Jan 17, 2026. It is now read-only.

Commit 01ffa80

Browse files
author
Jade Turner
committed
[drive] Add custom weighted twist pose estimator
Currently we just weight drive measurements to 1 so this should be basically the same as what we had before. Signed-off-by: Jade Turner <spacey-sooty@proton.me>
1 parent b930ead commit 01ffa80

File tree

3 files changed

+163
-15
lines changed

3 files changed

+163
-15
lines changed

src/main/java/org/curtinfrc/frc2025/subsystems/drive/Drive.java

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -11,10 +11,10 @@
1111
import edu.wpi.first.hal.FRCNetComm.tResourceType;
1212
import edu.wpi.first.hal.HAL;
1313
import edu.wpi.first.math.MathUtil;
14-
import edu.wpi.first.math.Matrix;
14+
import edu.wpi.first.math.VecBuilder;
15+
import edu.wpi.first.math.Vector;
1516
import edu.wpi.first.math.controller.PIDController;
1617
import edu.wpi.first.math.controller.ProfiledPIDController;
17-
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
1818
import edu.wpi.first.math.filter.SlewRateLimiter;
1919
import edu.wpi.first.math.geometry.Pose2d;
2020
import edu.wpi.first.math.geometry.Pose3d;
@@ -26,7 +26,6 @@
2626
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
2727
import edu.wpi.first.math.kinematics.SwerveModulePosition;
2828
import edu.wpi.first.math.kinematics.SwerveModuleState;
29-
import edu.wpi.first.math.numbers.N1;
3029
import edu.wpi.first.math.numbers.N3;
3130
import edu.wpi.first.math.trajectory.TrapezoidProfile;
3231
import edu.wpi.first.math.util.Units;
@@ -73,8 +72,8 @@ public class Drive extends SubsystemBase {
7372
new SwerveModulePosition(),
7473
new SwerveModulePosition()
7574
};
76-
private SwerveDrivePoseEstimator poseEstimator =
77-
new SwerveDrivePoseEstimator(kinematics, rawGyroRotation, lastModulePositions, Pose2d.kZero);
75+
private PoseEstimator poseEstimator =
76+
new PoseEstimator(kinematics, lastModulePositions, rawGyroRotation);
7877

7978
private final PIDController xController = new PIDController(10.0, 0.0, 0.0);
8079
private final PIDController yController = new PIDController(10.0, 0.0, 0.0);
@@ -166,6 +165,8 @@ public void periodic() {
166165
lastModulePositions[moduleIndex] = modulePositions[moduleIndex];
167166
}
168167

168+
Logger.recordOutput("ModuleDeltas", moduleDeltas);
169+
169170
// Update gyro angle
170171
if (gyroInputs.connected) {
171172
// Use the real gyro angle
@@ -177,7 +178,8 @@ public void periodic() {
177178
}
178179

179180
// Apply update
180-
poseEstimator.updateWithTime(sampleTimestamps[i], rawGyroRotation, modulePositions);
181+
poseEstimator.updateWithTime(
182+
modulePositions, rawGyroRotation, sampleTimestamps[i], VecBuilder.fill(1, 1, 1));
181183
}
182184

183185
// Update gyro alert
@@ -551,7 +553,7 @@ public double getFFCharacterizationVelocity() {
551553
/** Returns the current odometry pose. */
552554
@AutoLogOutput(key = "Odometry/Robot")
553555
public Pose2d getPose() {
554-
return poseEstimator.getEstimatedPosition();
556+
return poseEstimator.getEstimatedPose();
555557
}
556558

557559
/** Returns the current odometry rotation. */
@@ -566,9 +568,7 @@ public void setPose(Pose2d pose) {
566568

567569
/** Adds a new timestamped vision measurement. */
568570
public void addVisionMeasurement(
569-
Pose2d visionRobotPoseMeters,
570-
double timestampSeconds,
571-
Matrix<N3, N1> visionMeasurementStdDevs) {
571+
Pose2d visionRobotPoseMeters, double timestampSeconds, Vector<N3> visionMeasurementStdDevs) {
572572
poseEstimator.addVisionMeasurement(
573573
visionRobotPoseMeters, timestampSeconds, visionMeasurementStdDevs);
574574
}
Lines changed: 151 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,151 @@
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+
import org.littletonrobotics.junction.Logger;
14+
15+
public class PoseEstimator {
16+
private static final double kMaxSampleAge = 0.3;
17+
18+
private final class TimestampedTwist2d extends Twist2d {
19+
public final double timestamp;
20+
21+
public TimestampedTwist2d(double dx, double dy, double dtheta, double timestamp) {
22+
super(dx, dy, dtheta);
23+
this.timestamp = timestamp;
24+
}
25+
}
26+
27+
private final LinkedList<TimestampedTwist2d> samples = new LinkedList<>();
28+
private Pose2d rootPose = new Pose2d();
29+
private final SwerveModulePosition[] prevWheelPositions;
30+
private final SwerveDriveKinematics kinematics;
31+
private Rotation2d gyroOffset;
32+
private Rotation2d prevAngle;
33+
34+
public PoseEstimator(
35+
SwerveDriveKinematics kinematics,
36+
SwerveModulePosition[] wheelPositions,
37+
Rotation2d gyroAngle) {
38+
this.kinematics = kinematics;
39+
prevWheelPositions = kinematics.copy(wheelPositions);
40+
gyroOffset = rootPose.getRotation().minus(gyroAngle);
41+
prevAngle = rootPose.getRotation();
42+
}
43+
44+
public void resetPosition(
45+
Rotation2d gyroAngle, SwerveModulePosition[] wheelPositions, Pose2d pose) {
46+
rootPose = pose;
47+
prevAngle = pose.getRotation();
48+
gyroOffset = pose.getRotation().minus(gyroAngle);
49+
kinematics.copyInto(wheelPositions, prevWheelPositions);
50+
samples.clear();
51+
}
52+
53+
private OptionalInt indexForTimestamp(double timestamp) {
54+
if (samples.isEmpty()) {
55+
return OptionalInt.empty();
56+
}
57+
58+
if (samples.getFirst().timestamp > timestamp) {
59+
return OptionalInt.empty();
60+
}
61+
if (samples.getLast().timestamp < timestamp) {
62+
return OptionalInt.of(samples.size() - 1);
63+
}
64+
int low = 0;
65+
int high = samples.size() - 1;
66+
while (low <= high) {
67+
int mid = (low + high) / 2;
68+
double midTime = samples.get(mid).timestamp;
69+
if (midTime < timestamp) {
70+
low = mid + 1;
71+
} else if (midTime > timestamp) {
72+
high = mid - 1;
73+
} else {
74+
return OptionalInt.of(mid);
75+
}
76+
}
77+
return OptionalInt.of(low - 1);
78+
}
79+
80+
private Pose2d poseAtIndex(int index) {
81+
// switching this over to primitive math would be a good idea
82+
Pose2d pose = rootPose;
83+
for (int i = 0; i < index; i++) {
84+
pose = pose.exp(samples.get(i));
85+
}
86+
return pose;
87+
}
88+
89+
private void pruneToRoot() {
90+
while (!samples.isEmpty()
91+
&& samples.getFirst().timestamp < RobotController.getTime() - kMaxSampleAge) {
92+
rootPose = rootPose.exp(samples.removeFirst());
93+
}
94+
}
95+
96+
/**
97+
* Adds a sample to the estimator
98+
*
99+
* @param pose the pose of the robot at the time of the sample
100+
* @param timestamp the timestamp of the sample
101+
* @param weight the weight of the sample (0.0 to 1.0)
102+
*/
103+
public void addVisionMeasurement(Pose2d pose, double timestamp, Vector<N3> weight) {
104+
var opt = indexForTimestamp(timestamp);
105+
if (opt.isEmpty()) {
106+
// timestamp is before the first sample
107+
return;
108+
}
109+
int index = opt.getAsInt();
110+
111+
Pose2d lastPose = poseAtIndex(index);
112+
Twist2d twist = lastPose.log(pose);
113+
samples.add(
114+
index,
115+
new TimestampedTwist2d(
116+
twist.dx * weight.get(0),
117+
twist.dy * weight.get(1),
118+
twist.dtheta * weight.get(2),
119+
timestamp));
120+
pruneToRoot();
121+
}
122+
123+
public void updateWithTime(
124+
SwerveModulePosition[] wheelPositions,
125+
Rotation2d gyroAngle,
126+
double timestamp,
127+
Vector<N3> weight) {
128+
var angle = gyroAngle.plus(gyroOffset);
129+
var twist = kinematics.toTwist2d(prevWheelPositions, wheelPositions);
130+
twist.dtheta = angle.minus(prevAngle).getRadians();
131+
Logger.recordOutput("PoseEstimator/PreviousWheelPositions", prevWheelPositions);
132+
Logger.recordOutput("PoseEstimator/CurrentWheelPositions", wheelPositions);
133+
Logger.recordOutput("PoseEstimator/Samples", samples.size());
134+
Logger.recordOutput("PoseEstimator/Twist", twist);
135+
136+
samples.add(
137+
new TimestampedTwist2d(
138+
twist.dx * weight.get(0),
139+
twist.dy * weight.get(1),
140+
twist.dtheta * weight.get(2),
141+
timestamp));
142+
143+
kinematics.copyInto(wheelPositions, prevWheelPositions);
144+
prevAngle = angle;
145+
pruneToRoot();
146+
}
147+
148+
public Pose2d getEstimatedPose() {
149+
return poseAtIndex(samples.size());
150+
}
151+
}

src/main/java/org/curtinfrc/frc2025/subsystems/vision/Vision.java

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -15,12 +15,11 @@
1515

1616
import static org.curtinfrc.frc2025.subsystems.vision.VisionConstants.*;
1717

18-
import edu.wpi.first.math.Matrix;
1918
import edu.wpi.first.math.VecBuilder;
19+
import edu.wpi.first.math.Vector;
2020
import edu.wpi.first.math.geometry.Pose2d;
2121
import edu.wpi.first.math.geometry.Pose3d;
2222
import edu.wpi.first.math.geometry.Rotation2d;
23-
import edu.wpi.first.math.numbers.N1;
2423
import edu.wpi.first.math.numbers.N3;
2524
import edu.wpi.first.wpilibj.Alert;
2625
import edu.wpi.first.wpilibj.Alert.AlertType;
@@ -187,8 +186,6 @@ public void periodic() {
187186
@FunctionalInterface
188187
public static interface PoseEstimateConsumer {
189188
public void accept(
190-
Pose2d visionRobotPoseMeters,
191-
double timestampSeconds,
192-
Matrix<N3, N1> visionMeasurementStdDevs);
189+
Pose2d visionRobotPoseMeters, double timestampSeconds, Vector<N3> visionMeasurementStdDevs);
193190
}
194191
}

0 commit comments

Comments
 (0)