diff --git a/src/main/java/org/carlmontrobotics/subsystems/Arm.java b/src/main/java/org/carlmontrobotics/subsystems/Arm.java index 6d3ff393..745b45f6 100644 --- a/src/main/java/org/carlmontrobotics/subsystems/Arm.java +++ b/src/main/java/org/carlmontrobotics/subsystems/Arm.java @@ -233,7 +233,8 @@ public TrapezoidProfile.State getCurrentArmGoal() { public boolean armAtSetpoint() { - return armProfile.isFinished(armProfileTimer.get()); + return Math.abs(getArmPos() - goalState.position) < POS_TOLERANCE_RAD && + Math.abs(getArmVel() - goalState.velocity) < VEL_TOLERANCE_RAD_P_SEC; }