From 459bf30a3e8ba8d3f324b9ad6f94188056796bee Mon Sep 17 00:00:00 2001 From: rickyegl <135090025+rickyegl@users.noreply.github.com> Date: Thu, 8 Jan 2026 22:46:49 -0600 Subject: [PATCH 1/3] Fixed double Speeds.vx in Math.hypot from slowEnoughToRaiseElevator --- src/main/java/frc/robot/trajectories/FollowSyncedPIDToPose.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/trajectories/FollowSyncedPIDToPose.java b/src/main/java/frc/robot/trajectories/FollowSyncedPIDToPose.java index 3e1b15a..a05df43 100644 --- a/src/main/java/frc/robot/trajectories/FollowSyncedPIDToPose.java +++ b/src/main/java/frc/robot/trajectories/FollowSyncedPIDToPose.java @@ -85,7 +85,7 @@ public boolean closeEnoughToRaiseElevator() { public boolean slowEnoughToRaiseElevator() { return Math.hypot( Drive.mInstance.getState().Speeds.vx, - Drive.mInstance.getState().Speeds.vx) + Drive.mInstance.getState().Speeds.vy) < velToRaiseElevator.in(Units.MetersPerSecond); } From 20b14d02f64b4491ab2e12cb7e7f716da551666a Mon Sep 17 00:00:00 2001 From: rickyegl <135090025+rickyegl@users.noreply.github.com> Date: Thu, 8 Jan 2026 22:49:11 -0600 Subject: [PATCH 2/3] Fixed double Speeds.vx in Math.hypot from slowEnoughToRaiseElevator on another file --- .../java/frc/robot/trajectories/FollowSyncedTrajectory.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/java/frc/robot/trajectories/FollowSyncedTrajectory.java b/src/main/java/frc/robot/trajectories/FollowSyncedTrajectory.java index ef0e05a..31177e0 100644 --- a/src/main/java/frc/robot/trajectories/FollowSyncedTrajectory.java +++ b/src/main/java/frc/robot/trajectories/FollowSyncedTrajectory.java @@ -67,7 +67,7 @@ public boolean closeEnoughToRaiseElevator() { public boolean slowEnoughToRaiseElevator() { return Math.hypot( Drive.mInstance.getState().Speeds.vx, - Drive.mInstance.getState().Speeds.vx) + Drive.mInstance.getState().Speeds.vy) < DriveConstants.kMaxSpeedTippy.times(1.1).in(Units.MetersPerSecond); } From e5b57101e685039846d6165537b610986fcbec68 Mon Sep 17 00:00:00 2001 From: rickyegl <135090025+rickyegl@users.noreply.github.com> Date: Thu, 8 Jan 2026 22:51:02 -0600 Subject: [PATCH 3/3] Fixed typo in Utils --- src/main/java/frc/lib/util/Util.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/java/frc/lib/util/Util.java b/src/main/java/frc/lib/util/Util.java index ea2dda8..a40cc8c 100644 --- a/src/main/java/frc/lib/util/Util.java +++ b/src/main/java/frc/lib/util/Util.java @@ -363,9 +363,9 @@ public void clearStatesBeforeTime(Time time) { } public Pose2dTimeInterpolable(Trajectory trajwithTan, Rotation2d startHeading, Rotation2d endHeading) { - double totalTimeSecpnods = trajwithTan.getTotalTime(); + double totalTimeSeconds = trajwithTan.getTotalTime(); for (State state : trajwithTan.getStates()) { - Rotation2d poseRotation = startHeading.interpolate(endHeading, state.time / totalTimeSecpnods); + Rotation2d poseRotation = startHeading.interpolate(endHeading, state.time / totalTimeSeconds); poseList.add(new Pair<>( new Pose2d(state.pose.getTranslation(), poseRotation), Units.Seconds.of(state.time)));