Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 5ff6eec

Browse files
committed
fix: Disable heading motion profile.
1 parent 8c91868 commit 5ff6eec

File tree

2 files changed

+10
-8
lines changed

2 files changed

+10
-8
lines changed

Diff for: src/main/java/frc/robot/odometry/Odometry.java

+2
Original file line numberDiff line numberDiff line change
@@ -151,6 +151,8 @@ public Rotation2d getFieldRelativeHeading() {
151151
* alliance.
152152
*/
153153
public Rotation2d getDriverRelativeHeading() {
154+
gyroscope.update(gyroscopeValues);
155+
154156
return Rotation2d.fromRotations(gyroscopeValues.yawRotations);
155157
}
156158

Diff for: src/main/java/frc/robot/swerve/DriveCommand.java

+8-8
Original file line numberDiff line numberDiff line change
@@ -73,22 +73,22 @@ public void execute() {
7373

7474
Rotation2d driverRelativeHeading = odometry.getDriverRelativeHeading();
7575

76-
if (DriveRequest.startedDrifting(previousRequest, request)) {
77-
resetHeadingGoal();
78-
}
76+
// if (DriveRequest.startedDrifting(previousRequest, request)) {
77+
// resetHeadingGoal();
78+
// }
7979

80-
if (request.isSnapping()) {
81-
setPositionHeadingGoal(headingSnapper.snap(request.driverHeading()));
82-
}
80+
// if (request.isSnapping()) {
81+
// setPositionHeadingGoal(headingSnapper.snap(request.driverHeading()));
82+
// }
8383

84-
Rotation2d omega;
84+
Rotation2d omega = new Rotation2d();
8585

8686
if (request.isSpinning()) {
8787
updateVelocity(request.omega());
8888

8989
omega = request.omega();
9090
} else {
91-
omega = calculateHeadingProfileOmega();
91+
// omega = calculateHeadingProfileOmega();
9292
}
9393

9494
ChassisSpeeds chassisSpeeds =

0 commit comments

Comments
 (0)