Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/main/java/frc/lib/util/Util.java
Original file line number Diff line number Diff line change
Expand Up @@ -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)));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand Down