Skip to content

Commit

Permalink
[wpimath] Clean up arm and elevator feedforward APIs
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul committed Dec 27, 2024
1 parent 2a757ea commit 8a21bc0
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 66 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -110,8 +110,7 @@ public void reachGoal(double goal) {

// With the setpoint value we run PID control like normal
double pidOutput = m_pidController.calculate(m_encoder.getDistance(), m_setpoint.position);
double feedforwardOutput =
m_feedforward.calculateWithVelocities(m_setpoint.velocity, next.velocity);
double feedforwardOutput = m_feedforward.calculate(m_setpoint.velocity, next.velocity);

m_motor.setVoltage(pidOutput + feedforwardOutput);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,37 +131,18 @@ public double getDt() {
return m_dt;
}

/**
* Calculates the feedforward from the gains and setpoints.
*
* @param positionRadians The position (angle) setpoint. This angle should be measured from the
* horizontal (i.e. if the provided angle is 0, the arm should be parallel with the floor). If
* your encoder does not follow this convention, an offset should be added.
* @param velocityRadPerSec The velocity setpoint.
* @param accelRadPerSecSquared The acceleration setpoint.
* @return The computed feedforward.
*/
@Deprecated(forRemoval = true, since = "2025")
public double calculate(
double positionRadians, double velocityRadPerSec, double accelRadPerSecSquared) {
return ks * Math.signum(velocityRadPerSec)
+ kg * Math.cos(positionRadians)
+ kv * velocityRadPerSec
+ ka * accelRadPerSecSquared;
}

/**
* Calculates the feedforward from the gains and velocity setpoint assuming continuous control
* (acceleration is assumed to be zero).
*
* @param positionRadians The position (angle) setpoint. This angle should be measured from the
* @param position The position setpoint in radians. This angle should be measured from the
* horizontal (i.e. if the provided angle is 0, the arm should be parallel with the floor). If
* your encoder does not follow this convention, an offset should be added.
* @param velocity The velocity setpoint.
* @param velocity The velocity setpoint in radians per second.
* @return The computed feedforward.
*/
public double calculate(double positionRadians, double velocity) {
return calculate(positionRadians, velocity, 0);
public double calculate(double position, double velocity) {
return ks * Math.signum(velocity) + kg * Math.cos(position) + kv * velocity;
}

/**
Expand All @@ -172,29 +153,9 @@ public double calculate(double positionRadians, double velocity) {
* your encoder does not follow this convention, an offset should be added.
* @param currentVelocity The current velocity setpoint in radians per second.
* @param nextVelocity The next velocity setpoint in radians per second.
* @param dt Time between velocity setpoints in seconds.
* @return The computed feedforward in volts.
*/
@SuppressWarnings("removal")
@Deprecated(forRemoval = true, since = "2025")
public double calculate(
double currentAngle, double currentVelocity, double nextVelocity, double dt) {
return ArmFeedforwardJNI.calculate(
ks, kv, ka, kg, currentAngle, currentVelocity, nextVelocity, dt);
}

/**
* Calculates the feedforward from the gains and setpoints assuming discrete control.
*
* @param currentAngle The current angle in radians. This angle should be measured from the
* horizontal (i.e. if the provided angle is 0, the arm should be parallel to the floor). If
* your encoder does not follow this convention, an offset should be added.
* @param currentVelocity The current velocity setpoint in radians per second.
* @param nextVelocity The next velocity setpoint in radians per second.
* @return The computed feedforward in volts.
*/
public double calculateWithVelocities(
double currentAngle, double currentVelocity, double nextVelocity) {
public double calculate(double currentAngle, double currentVelocity, double nextVelocity) {
return ArmFeedforwardJNI.calculate(
ks, kv, ka, kg, currentAngle, currentVelocity, nextVelocity, m_dt);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,28 +131,15 @@ public double getDt() {
return m_dt;
}

/**
* Calculates the feedforward from the gains and setpoints assuming continuous control.
*
* @param velocity The velocity setpoint.
* @param acceleration The acceleration setpoint.
* @return The computed feedforward.
*/
@SuppressWarnings("removal")
@Deprecated(forRemoval = true, since = "2025")
public double calculate(double velocity, double acceleration) {
return ks * Math.signum(velocity) + kg + kv * velocity + ka * acceleration;
}

/**
* Calculates the feedforward from the gains and velocity setpoint assuming continuous control
* (acceleration is assumed to be zero).
*
* @param velocity The velocity setpoint.
* @param velocity The velocity setpoint in meters per second.
* @return The computed feedforward.
*/
public double calculate(double velocity) {
return calculate(velocity, 0);
return calculate(velocity, velocity);
}

/**
Expand All @@ -162,9 +149,9 @@ public double calculate(double velocity) {
*
* @param currentVelocity The current velocity setpoint in meters per second.
* @param nextVelocity The next velocity setpoint in meters per second.
* @return The computed feedforward in volts.
* @return The computed feedforward.
*/
public double calculateWithVelocities(double currentVelocity, double nextVelocity) {
public double calculate(double currentVelocity, double nextVelocity) {
// See wpimath/algorithms.md#Elevator_feedforward for derivation
if (ka == 0.0) {
return ks * Math.signum(nextVelocity) + kg + kv * nextVelocity;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,7 @@ private Matrix<N2, N1> simulate(
*/
private void calculateAndSimulate(
double currentAngle, double currentVelocity, double nextVelocity, double dt) {
final double input =
m_armFF.calculateWithVelocities(currentAngle, currentVelocity, nextVelocity);
final double input = m_armFF.calculate(currentAngle, currentVelocity, nextVelocity);
assertEquals(nextVelocity, simulate(currentAngle, currentVelocity, input, dt).get(1, 0), 1e-12);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ void testCalculate() {
var nextR = VecBuilder.fill(3.0);
assertEquals(
plantInversion.calculate(r, nextR).get(0, 0) + ks + kg,
m_elevatorFF.calculateWithVelocities(2.0, 3.0),
m_elevatorFF.calculate(2.0, 3.0),
0.002);
}

Expand Down

0 comments on commit 8a21bc0

Please sign in to comment.