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

Commit e4215c8

Browse files
committed
works better
Signed-off-by: Jade Turner <spacey-sooty@proton.me>
1 parent a1b802a commit e4215c8

File tree

5 files changed

+89
-5
lines changed

5 files changed

+89
-5
lines changed

src/main/java/org/curtinfrc/frc2025/Constants.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,9 +16,9 @@
1616
* (log replay from a file).
1717
*/
1818
public final class Constants {
19-
public static final RobotType robotType = RobotType.SIMBOT;
20-
public static final double ROBOT_X = 660; // mm
21-
public static final double ROBOT_Y = 680;
19+
public static final RobotType robotType = RobotType.DEVBOT;
20+
public static final double ROBOT_X = 550; // mm
21+
public static final double ROBOT_Y = 570;
2222

2323
public static final Mode getMode() {
2424
return switch (robotType) {

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

Lines changed: 33 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
import edu.wpi.first.math.numbers.N3;
3030
import edu.wpi.first.math.trajectory.TrapezoidProfile;
3131
import edu.wpi.first.math.util.Units;
32+
import edu.wpi.first.util.CircularBuffer;
3233
import edu.wpi.first.wpilibj.Alert;
3334
import edu.wpi.first.wpilibj.Alert.AlertType;
3435
import edu.wpi.first.wpilibj.DriverStation;
@@ -50,6 +51,7 @@
5051
import org.curtinfrc.frc2025.Constants;
5152
import org.curtinfrc.frc2025.Constants.Mode;
5253
import org.curtinfrc.frc2025.generated.TunerConstants;
54+
import org.curtinfrc.frc2025.util.BufferUtil;
5355
import org.curtinfrc.frc2025.util.RepulsorFieldPlanner;
5456
import org.littletonrobotics.junction.AutoLogOutput;
5557
import org.littletonrobotics.junction.Logger;
@@ -75,6 +77,9 @@ public class Drive extends SubsystemBase {
7577
};
7678
private PoseEstimator poseEstimator =
7779
new PoseEstimator(kinematics, lastModulePositions, rawGyroRotation);
80+
private CircularBuffer<Double> xAcceleration = new CircularBuffer<Double>(6);
81+
private CircularBuffer<Double> yAcceleration = new CircularBuffer<Double>(6);
82+
private ChassisSpeeds lastChassisSpeeds = new ChassisSpeeds();
7883

7984
private double p = 6;
8085
private double d = 0.2;
@@ -194,12 +199,38 @@ public void periodic() {
194199
} else {
195200
// Fallback to calculating the angle delta
196201
Twist2d twist = kinematics.toTwist2d(moduleDeltas);
202+
// Use the angle delta from the kinematics and module deltas
197203
rawGyroRotation = rawGyroRotation.plus(new Rotation2d(twist.dtheta));
198204
}
199205

206+
var chassisSpeedsDiff = getChassisSpeeds().minus(lastChassisSpeeds);
207+
var xAccel = chassisSpeedsDiff.vxMetersPerSecond / 0.02;
208+
xAcceleration.addLast(xAccel);
209+
var yAccel = chassisSpeedsDiff.vyMetersPerSecond / 0.02;
210+
yAcceleration.addLast(yAccel);
211+
var avgX = BufferUtil.average(xAcceleration);
212+
var avgY = BufferUtil.average(yAcceleration);
213+
Logger.recordOutput("FilteredAccelerationX", avgX);
214+
Logger.recordOutput("AccelerationX", chassisSpeedsDiff.vxMetersPerSecond / 0.02);
215+
Logger.recordOutput("AccelerationY", chassisSpeedsDiff.vyMetersPerSecond / 0.02);
216+
Logger.recordOutput(
217+
"Difference",
218+
Math.abs(chassisSpeedsDiff.vxMetersPerSecond / 0.02 - gyroInputs.xAcceleration));
219+
var xDiff = Math.abs(avgX - gyroIO.xAcceleration());
220+
Logger.recordOutput("FilteredDifference", xDiff);
221+
var yDiff = Math.abs(avgY - gyroIO.yAcceleration());
222+
if (xDiff < 1) {
223+
xDiff = 1;
224+
}
225+
if (yDiff < 1) {
226+
yDiff = 1;
227+
}
200228
// Apply update
201229
poseEstimator.updateWithTime(
202-
modulePositions, rawGyroRotation, sampleTimestamps[i], VecBuilder.fill(1, 1, 1));
230+
modulePositions,
231+
rawGyroRotation,
232+
sampleTimestamps[i],
233+
VecBuilder.fill(1 / xDiff, 1 / yDiff, 1));
203234
}
204235

205236
Logger.recordOutput("Drive/xPID/setpoint", xController.getSetpoint());
@@ -212,6 +243,7 @@ public void periodic() {
212243

213244
// Update gyro alert
214245
gyroDisconnectedAlert.set(!gyroInputs.connected && Constants.getMode() != Mode.SIM);
246+
lastChassisSpeeds = getChassisSpeeds();
215247
}
216248

217249
/**

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

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515

1616
import edu.wpi.first.math.geometry.Rotation2d;
1717
import org.littletonrobotics.junction.AutoLog;
18+
import org.littletonrobotics.junction.AutoLogOutput;
1819

1920
public interface GyroIO {
2021
@AutoLog
@@ -24,7 +25,19 @@ public static class GyroIOInputs {
2425
public double yawVelocityRadPerSec = 0.0;
2526
public double[] odometryYawTimestamps = new double[] {};
2627
public Rotation2d[] odometryYawPositions = new Rotation2d[] {};
28+
public double xAcceleration = 0;
29+
public double yAcceleration = 0;
2730
}
2831

2932
public default void updateInputs(GyroIOInputs inputs) {}
33+
34+
@AutoLogOutput(key = "Gyro/FilteredXAcceleration")
35+
public default double xAcceleration() {
36+
return 0;
37+
}
38+
39+
@AutoLogOutput(key = "Gyro/FilteredYAcceleration")
40+
public default double yAcceleration() {
41+
return 0;
42+
}
3043
}

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

Lines changed: 25 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313

1414
package org.curtinfrc.frc2025.subsystems.drive;
1515

16+
import static edu.wpi.first.units.Units.MetersPerSecondPerSecond;
1617
import static org.curtinfrc.frc2025.subsystems.drive.DriveConstants.*;
1718

1819
import com.ctre.phoenix6.BaseStatusSignal;
@@ -24,8 +25,11 @@
2425
import edu.wpi.first.math.util.Units;
2526
import edu.wpi.first.units.measure.Angle;
2627
import edu.wpi.first.units.measure.AngularVelocity;
28+
import edu.wpi.first.units.measure.LinearAcceleration;
29+
import edu.wpi.first.util.CircularBuffer;
2730
import java.util.Queue;
2831
import org.curtinfrc.frc2025.generated.TunerConstants;
32+
import org.curtinfrc.frc2025.util.BufferUtil;
2933

3034
/** IO implementation for Pigeon 2. */
3135
public class GyroIOPigeon2 implements GyroIO {
@@ -34,9 +38,13 @@ public class GyroIOPigeon2 implements GyroIO {
3438
TunerConstants.DrivetrainConstants.Pigeon2Id,
3539
TunerConstants.DrivetrainConstants.CANBusName);
3640
private final StatusSignal<Angle> yaw = pigeon.getYaw();
41+
private final StatusSignal<LinearAcceleration> xAcceleration = pigeon.getAccelerationX();
42+
private final StatusSignal<LinearAcceleration> yAcceleration = pigeon.getAccelerationY();
3743
private final Queue<Double> yawPositionQueue;
3844
private final Queue<Double> yawTimestampQueue;
3945
private final StatusSignal<AngularVelocity> yawVelocity = pigeon.getAngularVelocityZWorld();
46+
private final CircularBuffer<Double> xAccelerationBuffer = new CircularBuffer<>(6);
47+
private final CircularBuffer<Double> yAccelerationBuffer = new CircularBuffer<>(6);
4048

4149
public GyroIOPigeon2() {
4250
pigeon.getConfigurator().apply(new Pigeon2Configuration());
@@ -50,7 +58,9 @@ public GyroIOPigeon2() {
5058

5159
@Override
5260
public void updateInputs(GyroIOInputs inputs) {
53-
inputs.connected = BaseStatusSignal.refreshAll(yaw, yawVelocity).equals(StatusCode.OK);
61+
inputs.connected =
62+
BaseStatusSignal.refreshAll(yaw, yawVelocity, xAcceleration, yAcceleration)
63+
.equals(StatusCode.OK);
5464
inputs.yawPosition = Rotation2d.fromDegrees(yaw.getValueAsDouble());
5565
inputs.yawVelocityRadPerSec = Units.degreesToRadians(yawVelocity.getValueAsDouble());
5666

@@ -60,7 +70,21 @@ public void updateInputs(GyroIOInputs inputs) {
6070
yawPositionQueue.stream()
6171
.map((Double value) -> Rotation2d.fromDegrees(value))
6272
.toArray(Rotation2d[]::new);
73+
inputs.xAcceleration = xAcceleration.getValue().in(MetersPerSecondPerSecond);
74+
xAccelerationBuffer.addLast(inputs.xAcceleration);
75+
inputs.yAcceleration = yAcceleration.getValue().in(MetersPerSecondPerSecond);
76+
yAccelerationBuffer.addLast(inputs.yAcceleration);
6377
yawTimestampQueue.clear();
6478
yawPositionQueue.clear();
6579
}
80+
81+
@Override
82+
public double xAcceleration() {
83+
return BufferUtil.average(xAccelerationBuffer);
84+
}
85+
86+
@Override
87+
public double yAcceleration() {
88+
return BufferUtil.average(yAccelerationBuffer);
89+
}
6690
}
Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
package org.curtinfrc.frc2025.util;
2+
3+
import edu.wpi.first.util.CircularBuffer;
4+
5+
public class BufferUtil {
6+
private BufferUtil() {}
7+
8+
public static Double average(CircularBuffer<Double> buffer) {
9+
Double total = 0.0;
10+
for (var i = 0; i < buffer.size(); i++) {
11+
total += buffer.get(i);
12+
}
13+
return total;
14+
}
15+
}

0 commit comments

Comments
 (0)