Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Java SimpleMotorFeedforward API is chaotic #63

Open
chauser opened this issue Dec 5, 2024 · 3 comments
Open

Java SimpleMotorFeedforward API is chaotic #63

chauser opened this issue Dec 5, 2024 · 3 comments

Comments

@chauser
Copy link

chauser commented Dec 5, 2024

The discussion in wpilibsuite/allwpilib#7280 illuminates some of the decisions regarding deprecation of the calculate(double) and calculate(double, double) methods. But the whole API is what I would call chaotic: it encourages use of the Units versions of calculate (by deprecating the double-taking versions). But apart from calculate all of the other methods ({max,min}Achievable{Velocity,Acceleration}) exist only in double-taking/returning versions.

Also, I recall reading somewhere (and I could be wrong) that WPILib math support generally supports a continuous view of the world from the outside, discretizing as needed internally. Having the new, undeprecated two parameter calculate take currentVelocity and nextVelocity arguments seems to go against this philosophy. And it seems to me quite awkward to use if you conceive your desired behavior in terms of acceleration--essentially requiring the using code to do the discretization. It is also at odds with the interface of the {max,min}Achievable{Velocity,Acceleration} methods -- part of the overall chaos of the API.

The deprecation message for the double-taking single parameter calculate is also misleading as it points to the current/next velocity overload rather than the single-parameter units-taking overload.

This was all really confusing and has taken hours to understand. I don't mind that as a beta tester but it would be nice if it wasn't that painful for teams using the season release.

@calcmogul
Copy link
Member

calcmogul commented Dec 5, 2024

it encourages use of the Units versions of calculate (by deprecating the double-taking versions). But apart from calculate all of the other methods ({max,min}Achievable{Velocity,Acceleration}) exist only in double-taking/returning versions.

Normally, we'd only provide double-taking versions because the Java units API has too much overhead on the roboRIO, but we used units in this specific case to disambiguate the calculate(velocity, acceleration) and calculate(currentVelocity, nextVelocity) overloads without having to use worse naming for one of them. Ideally, all Java APIs would use units like C++, but we'll need the compute power of SystemCore's Raspberry Pi Compute Module 5 to do that.

Also, I recall reading somewhere (and I could be wrong) that WPILib math support generally supports a continuous view of the world from the outside, discretizing as needed internally.

We only do this for system models that need to be numerically integrated at runtime based on a provided dt. System models are also more natural to represent as differential equations and easier to obtain than difference equations.

On the other hand, feedforward and feedback controllers in FRC are inherently discrete because they are updated at discrete intervals (i.e., we're not doing continuous feedback with op-amps). For a constant voltage applied for one timestep, the acceleration of a DC motor continuously varies, so using a constant (usually average) acceleration as a feedforward input produces inaccurate results. The calculate(currentVelocity, nextVelocity) overload handles this correctly and produces a more accurate feedforward voltage.

One can calculate the acceleration value one would have to use to produce the correct voltage, but it's not worth using since it's a workaround for using the wrong formulation of the problem: exact-accel-feedforward.md.

Having the new, undeprecated two parameter calculate take currentVelocity and nextVelocity arguments seems to go against this philosophy. And it seems to me quite awkward to use if you conceive your desired behavior in terms of acceleration--essentially requiring the using code to do the discretization.

Actually, most user code I see has to numerically differentiate velocity to get an acceleration setpoint for the calculate(velocity, acceleration) overload. Users are more likely to have a "next setpoint" available instead. Here's an example:

package frc.robot;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.trajectory.ExponentialProfile;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

@SuppressWarnings({"MemberName", "MissingJavadocMethod"})
public class Robot extends TimedRobot {
  public static final double dt = 0.01;
  public static final double offset = 0.005;

  public static final double Ks = 0.1;
  public static final double Kv = 3.0;
  public static final double Ka = 0.5;

  public static final double Kp = 0.1;
  public static final double Kd = 0.1;

  public Encoder encoder = new Encoder(0, 1);
  public PWMSparkMax motor = new PWMSparkMax(0);

  public ExponentialProfile profile =
      new ExponentialProfile(ExponentialProfile.Constraints.fromCharacteristics(10.0, Kv, Ka));

  public SimpleMotorFeedforward feedforward = new SimpleMotorFeedforward(Ks, Kv, Ka, dt);
  public PIDController feedback = new PIDController(Kp, 0.0, Kd, dt);

  public ExponentialProfile.State currentSetpoint = new ExponentialProfile.State();
  public ExponentialProfile.State goal = new ExponentialProfile.State();

  public Robot() {
    addPeriodic(this::controller, dt, offset);
  }

  public void setGoal(double goal) {
    this.goal.position = goal;
  }

  public void controller() {
    if (isDisabled()) {
      return;
    }

    var nextSetpoint = profile.calculate(dt, currentSetpoint, goal);
    motor.setVoltage(
        feedforward.calculate(currentSetpoint.velocity, nextSetpoint.velocity)
            + feedback.calculate(encoder.getDistance(), currentSetpoint.position));
    currentSetpoint = nextSetpoint;
  }
}

It is also at odds with the interface of the {max,min}Achievable{Velocity,Acceleration} methods -- part of the overall chaos of the API.

Those are legacy code from 2020. They're only relevant for dynamically computing trapezoid profile constraints, but ExponentialProfile is now a better option for that use case. We can probably deprecate them now, but I foresee pushback from other maintainers since it's ostensibly useful in the abstract.

The deprecation message for the double-taking single parameter calculate is also misleading as it points to the current/next velocity overload rather than the single-parameter units-taking overload.

We can fix that. wpilibsuite/allwpilib#7489

This was all really confusing and has taken hours to understand.

Yea... this is the struggle of trying to evolve an API toward being more mathematically correct within the limitations of Java's type system. In C++, the change was just deprecating calculate(velocity, acceleration) and adding calculate(currentVelocity, nextVelocity).

@chauser
Copy link
Author

chauser commented Dec 5, 2024

Thanks. That helps. And I think your suggestion about deprecating the other double-taking methods would help, too.
I'm still wondering why the calculate(double velocity) method had to be deprecated. I don't think that was ever answered in the discussion of wpilibsuite/allwpilib#7280. Our code is using a velocity extracted from a SwerveModuleState (a double) as input to the feedforward; the allocation pressure of creating a new Unit value each time is unattractive but so is a mutable Unit value. That said, it doesn't matter a whole lot to me because I expect all that code to be replaced this year.

@calcmogul
Copy link
Member

We reverted all the changes for 2025 in wpilibsuite/allwpilib#7489. We fixed the API for 2027 in wpilibsuite/allwpilib#7516.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants