mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Fix ProfiledPIDFeedForward after merge
This commit is contained in:
@@ -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;
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user