Skip to content

Commit 7423580

Browse files
Replace deprecated feedforward.calculate(velocity, acceleration) (#3117)
* Replace deprecated feedforward.calculate(velocity, acceleration) Update ProfiledPIDController documentation to use the recommended feedforward.calculate(currentVelocity, nextVelocity) overload instead of the deprecated (velocity, acceleration) version. This eliminates manual acceleration calculations and uses the newer API that calculates acceleration internally from velocity change. Fixes #2963 * Convert ProfiledPIDController feedforward example to use snippets Replace inline code blocks with RLIs to snippets from allwpilib. Java and C++ examples now reference compilable snippet code that will be tested in every allwpilib build. Python remains as inline code block since Python snippets are maintained in robotpy repository. Related: wpilibsuite/allwpilib#8280 * Manually update RLI --------- Co-authored-by: sciencewhiz <[email protected]>
1 parent ca83b6c commit 7423580

File tree

1 file changed

+25
-52
lines changed

1 file changed

+25
-52
lines changed

source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst

Lines changed: 25 additions & 52 deletions
Original file line numberDiff line numberDiff line change
@@ -84,58 +84,31 @@ The returned setpoint might then be used as in the following example:
8484

8585
.. tab-set-code::
8686

87-
```java
88-
double lastSpeed = 0;
89-
double lastTime = Timer.getFPGATimestamp();
90-
// Controls a simple motor's position using a SimpleMotorFeedforward
91-
// and a ProfiledPIDController
92-
public void goToPosition(double goalPosition) {
93-
double pidVal = controller.calculate(encoder.getDistance(), goalPosition);
94-
double acceleration = (controller.getSetpoint().velocity - lastSpeed) / (Timer.getFPGATimestamp() - lastTime);
95-
motor.setVoltage(
96-
pidVal
97-
+ feedforward.calculate(controller.getSetpoint().velocity, acceleration));
98-
lastSpeed = controller.getSetpoint().velocity;
99-
lastTime = Timer.getFPGATimestamp();
100-
}
101-
```
102-
103-
```c++
104-
units::meters_per_second_t lastSpeed = 0_mps;
105-
units::second_t lastTime = frc2::Timer::GetFPGATimestamp();
106-
// Controls a simple motor's position using a SimpleMotorFeedforward
107-
// and a ProfiledPIDController
108-
void GoToPosition(units::meter_t goalPosition) {
109-
auto pidVal = controller.Calculate(units::meter_t{encoder.GetDistance()}, goalPosition);
110-
auto acceleration = (controller.GetSetpoint().velocity - lastSpeed) /
111-
(frc2::Timer::GetFPGATimestamp() - lastTime);
112-
motor.SetVoltage(
113-
pidVal +
114-
feedforward.Calculate(controller.GetSetpoint().velocity, acceleration));
115-
lastSpeed = controller.GetSetpoint().velocity;
116-
lastTime = frc2::Timer::GetFPGATimestamp();
117-
}
118-
```
119-
120-
```python
121-
from wpilib import Timer
122-
from wpilib.controller import ProfiledPIDController
123-
from wpilib.controller import SimpleMotorFeedforward
124-
def __init__(self):
125-
# Assuming encoder, motor, controller are already defined
126-
self.lastSpeed = 0
127-
self.lastTime = Timer.getFPGATimestamp()
128-
# Assuming feedforward is a SimpleMotorFeedforward object
129-
self.feedforward = SimpleMotorFeedforward(ks=0.0, kv=0.0, ka=0.0)
130-
def goToPosition(self, goalPosition: float):
131-
pidVal = self.controller.calculate(self.encoder.getDistance(), goalPosition)
132-
acceleration = (self.controller.getSetpoint().velocity - self.lastSpeed) / (Timer.getFPGATimestamp() - self.lastTime)
133-
self.motor.setVoltage(
134-
pidVal
135-
+ self.feedforward.calculate(self.controller.getSetpoint().velocity, acceleration))
136-
self.lastSpeed = controller.getSetpoint().velocity
137-
self.lastTime = Timer.getFPGATimestamp()
138-
```
87+
.. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2026.1.1-beta-1/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/snippets/profiledpidfeedforward/Robot.java
88+
:language: java
89+
:lines: 37-44
90+
:lineno-match:
91+
92+
.. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2026.1.1-beta-1/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp
93+
:language: c++
94+
:lines: 25-32
95+
:lineno-match:
96+
97+
.. code-block:: python
98+
99+
from wpilib.controller import ProfiledPIDController
100+
from wpilib.controller import SimpleMotorFeedforward
101+
def __init__(self):
102+
# Assuming encoder, motor, controller are already defined
103+
self.lastSpeed = 0
104+
# Assuming feedforward is a SimpleMotorFeedforward object
105+
self.feedforward = SimpleMotorFeedforward(ks=0.0, kv=0.0, ka=0.0)
106+
def goToPosition(self, goalPosition: float):
107+
pidVal = self.controller.calculate(self.encoder.getDistance(), goalPosition)
108+
self.motor.setVoltage(
109+
pidVal
110+
+ self.feedforward.calculate(self.lastSpeed, self.controller.getSetpoint().velocity))
111+
self.lastSpeed = self.controller.getSetpoint().velocity
139112
140113
## Complete Usage Example
141114

0 commit comments

Comments
 (0)