From 3f88c287d6007f6be9fc5409aa9c42d41a504005 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sat, 1 Nov 2025 10:01:42 -0700 Subject: [PATCH] [examples] Fix ProfiledPIDFeedForward after merge --- .../first/wpilibj/snippets/profiledpidfeedforward/Robot.java | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java index 9f30e73e5f..4c60a509d7 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java @@ -37,9 +37,7 @@ public class Robot extends TimedRobot { public void goToPosition(double goalPosition) { double pidVal = m_controller.calculate(m_encoder.getDistance(), goalPosition); m_motor.setVoltage( - pidVal - + m_feedforward.calculateWithVelocities( - m_lastSpeed, m_controller.getSetpoint().velocity)); + pidVal + m_feedforward.calculate(m_lastSpeed, m_controller.getSetpoint().velocity)); m_lastSpeed = m_controller.getSetpoint().velocity; }