Skip to content

Commit af3b0c2

Browse files
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 af3b0c2

File tree

3 files changed

+156
-15
lines changed

3 files changed

+156
-15
lines changed

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

Lines changed: 8 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);
@@ -177,7 +176,8 @@ public void periodic() {
177176
}
178177

179178
// Apply update
180-
poseEstimator.updateWithTime(sampleTimestamps[i], rawGyroRotation, modulePositions);
179+
poseEstimator.updateWithTime(
180+
modulePositions, rawGyroRotation, sampleTimestamps[i], VecBuilder.fill(1, 1, 1));
181181
}
182182

183183
// Update gyro alert
@@ -551,7 +551,7 @@ public double getFFCharacterizationVelocity() {
551551
/** Returns the current odometry pose. */
552552
@AutoLogOutput(key = "Odometry/Robot")
553553
public Pose2d getPose() {
554-
return poseEstimator.getEstimatedPosition();
554+
return poseEstimator.getEstimatedPose();
555555
}
556556

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

567567
/** Adds a new timestamped vision measurement. */
568568
public void addVisionMeasurement(
569-
Pose2d visionRobotPoseMeters,
570-
double timestampSeconds,
571-
Matrix<N3, N1> visionMeasurementStdDevs) {
569+
Pose2d visionRobotPoseMeters, double timestampSeconds, Vector<N3> visionMeasurementStdDevs) {
572570
poseEstimator.addVisionMeasurement(
573571
visionRobotPoseMeters, timestampSeconds, visionMeasurementStdDevs);
574572
}
Lines changed: 146 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,146 @@
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+
}

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)