From 7ce82f79e1aa74433adec4969d74bf0920229f9b Mon Sep 17 00:00:00 2001 From: Brandon Date: Sat, 2 Mar 2024 21:45:56 -0800 Subject: [PATCH] fixed arm teleop --- src/main/java/org/carlmontrobotics/commands/ArmTeleop.java | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/java/org/carlmontrobotics/commands/ArmTeleop.java b/src/main/java/org/carlmontrobotics/commands/ArmTeleop.java index c06fb9e8..5e769975 100644 --- a/src/main/java/org/carlmontrobotics/commands/ArmTeleop.java +++ b/src/main/java/org/carlmontrobotics/commands/ArmTeleop.java @@ -52,7 +52,7 @@ public void execute() { double goalArmRad = goalState.position + speeds * deltaT; goalArmRad = MathUtil.clamp(goalArmRad, LOWER_ANGLE_LIMIT, UPPER_ANGLE_LIMIT); goalState = new TrapezoidProfile.State(goalArmRad, 0); - TrapezoidProfile.State setpoint = armSubsystem.calculateCustomSetPoint(armTimer.get(), armSubsystem.getCurrentArmState(), goalState); + TrapezoidProfile.State setpoint = armSubsystem.calculateCustomSetPoint(0.02, armSubsystem.getCurrentArmState(), goalState); armSubsystem.driveArm(setpoint.position); lastTime = currTime; } @@ -71,8 +71,6 @@ public double getRequestedSpeeds() { // Called once the command ends or is interrupted. @Override public void end(boolean interrupted) { - armTimer.stop(); - armTimer.reset(); } // Returns true when the command should end.