Class ArmFeedforward

java.lang.Object
edu.wpi.first.math.controller.ArmFeedforward
All Implemented Interfaces:
ProtobufSerializable, StructSerializable, WPISerializable

A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting against the force of gravity on a beam suspended at an angle).
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    static final ArmFeedforwardProto
    Arm feedforward protobuf for serialization.
    Arm feedforward struct for serialization.
  • Constructor Summary

    Constructors
    Constructor
    Description
    ArmFeedforward(double ks, double kg, double kv)
    Creates a new ArmFeedforward with the specified gains.
    ArmFeedforward(double ks, double kg, double kv, double ka)
    Creates a new ArmFeedforward with the specified gains.
    ArmFeedforward(double ks, double kg, double kv, double ka, double dtSeconds)
    Creates a new ArmFeedforward with the specified gains and period.
  • Method Summary

    Modifier and Type
    Method
    Description
    double
    calculate(double positionRadians, double velocity)
    Calculates the feedforward from the gains and velocity setpoint assuming continuous control (acceleration is assumed to be zero).
    double
    calculate(double positionRadians, double velocityRadPerSec, double accelRadPerSecSquared)
    Deprecated, for removal: This API element is subject to removal in a future version.
    double
    calculate(double currentAngle, double currentVelocity, double nextVelocity, double dt)
    Deprecated, for removal: This API element is subject to removal in a future version.
    double
    calculateWithVelocities(double currentAngle, double currentVelocity, double nextVelocity)
    Calculates the feedforward from the gains and setpoints assuming discrete control.
    double
    Returns the period in seconds.
    double
    Returns the acceleration gain in V/(rad/s²).
    double
    Returns the gravity gain in volts.
    double
    Returns the static gain in volts.
    double
    Returns the velocity gain in V/(rad/s).
    double
    maxAchievableAcceleration(double maxVoltage, double angle, double velocity)
    Calculates the maximum achievable acceleration given a maximum voltage supply, a position, and a velocity.
    double
    maxAchievableVelocity(double maxVoltage, double angle, double acceleration)
    Calculates the maximum achievable velocity given a maximum voltage supply, a position, and an acceleration.
    double
    minAchievableAcceleration(double maxVoltage, double angle, double velocity)
    Calculates the minimum achievable acceleration given a maximum voltage supply, a position, and a velocity.
    double
    minAchievableVelocity(double maxVoltage, double angle, double acceleration)
    Calculates the minimum achievable velocity given a maximum voltage supply, a position, and an acceleration.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

  • Constructor Details

    • ArmFeedforward

      public ArmFeedforward(double ks, double kg, double kv, double ka, double dtSeconds)
      Creates a new ArmFeedforward with the specified gains and period.
      Parameters:
      ks - The static gain in volts.
      kg - The gravity gain in volts.
      kv - The velocity gain in V/(rad/s).
      ka - The acceleration gain in V/(rad/s²).
      dtSeconds - The period in seconds.
      Throws:
      IllegalArgumentException - for kv < zero.
      IllegalArgumentException - for ka < zero.
      IllegalArgumentException - for period ≤ zero.
    • ArmFeedforward

      public ArmFeedforward(double ks, double kg, double kv, double ka)
      Creates a new ArmFeedforward with the specified gains. The period is defaulted to 20 ms.
      Parameters:
      ks - The static gain in volts.
      kg - The gravity gain in volts.
      kv - The velocity gain in V/(rad/s).
      ka - The acceleration gain in V/(rad/s²).
      Throws:
      IllegalArgumentException - for kv < zero.
      IllegalArgumentException - for ka < zero.
    • ArmFeedforward

      public ArmFeedforward(double ks, double kg, double kv)
      Creates a new ArmFeedforward with the specified gains. The period is defaulted to 20 ms.
      Parameters:
      ks - The static gain in volts.
      kg - The gravity gain in volts.
      kv - The velocity gain in V/(rad/s).
      Throws:
      IllegalArgumentException - for kv < zero.
  • Method Details

    • getKs

      public double getKs()
      Returns the static gain in volts.
      Returns:
      The static gain in volts.
    • getKg

      public double getKg()
      Returns the gravity gain in volts.
      Returns:
      The gravity gain in volts.
    • getKv

      public double getKv()
      Returns the velocity gain in V/(rad/s).
      Returns:
      The velocity gain.
    • getKa

      public double getKa()
      Returns the acceleration gain in V/(rad/s²).
      Returns:
      The acceleration gain.
    • getDt

      public double getDt()
      Returns the period in seconds.
      Returns:
      The period in seconds.
    • calculate

      @Deprecated(forRemoval=true, since="2025") public double calculate(double positionRadians, double velocityRadPerSec, double accelRadPerSecSquared)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Calculates the feedforward from the gains and setpoints.
      Parameters:
      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.
      velocityRadPerSec - The velocity setpoint.
      accelRadPerSecSquared - The acceleration setpoint.
      Returns:
      The computed feedforward.
    • calculate

      public double calculate(double positionRadians, double velocity)
      Calculates the feedforward from the gains and velocity setpoint assuming continuous control (acceleration is assumed to be zero).
      Parameters:
      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.
      velocity - The velocity setpoint.
      Returns:
      The computed feedforward.
    • calculate

      @Deprecated(forRemoval=true, since="2025") public double calculate(double currentAngle, double currentVelocity, double nextVelocity, double dt)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Calculates the feedforward from the gains and setpoints assuming continuous control.
      Parameters:
      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.
      currentVelocity - The current velocity setpoint in radians per second.
      nextVelocity - The next velocity setpoint in radians per second.
      dt - Time between velocity setpoints in seconds.
      Returns:
      The computed feedforward in volts.
    • calculateWithVelocities

      public double calculateWithVelocities(double currentAngle, double currentVelocity, double nextVelocity)
      Calculates the feedforward from the gains and setpoints assuming discrete control.
      Parameters:
      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.
      currentVelocity - The current velocity setpoint in radians per second.
      nextVelocity - The next velocity setpoint in radians per second.
      Returns:
      The computed feedforward in volts.
    • maxAchievableVelocity

      public double maxAchievableVelocity(double maxVoltage, double angle, double acceleration)
      Calculates the maximum achievable velocity given a maximum voltage supply, a position, and an acceleration. Useful for ensuring that velocity and acceleration constraints for a trapezoidal profile are simultaneously achievable - enter the acceleration constraint, and this will give you a simultaneously-achievable velocity constraint.
      Parameters:
      maxVoltage - The maximum voltage that can be supplied to the arm.
      angle - The angle of the arm, 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.
      acceleration - The acceleration of the arm, in (rad/s²).
      Returns:
      The maximum possible velocity in (rad/s) at the given acceleration and angle.
    • minAchievableVelocity

      public double minAchievableVelocity(double maxVoltage, double angle, double acceleration)
      Calculates the minimum achievable velocity given a maximum voltage supply, a position, and an acceleration. Useful for ensuring that velocity and acceleration constraints for a trapezoidal profile are simultaneously achievable - enter the acceleration constraint, and this will give you a simultaneously-achievable velocity constraint.
      Parameters:
      maxVoltage - The maximum voltage that can be supplied to the arm, in volts.
      angle - The angle of the arm, 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.
      acceleration - The acceleration of the arm, in (rad/s²).
      Returns:
      The minimum possible velocity in (rad/s) at the given acceleration and angle.
    • maxAchievableAcceleration

      public double maxAchievableAcceleration(double maxVoltage, double angle, double velocity)
      Calculates the maximum achievable acceleration given a maximum voltage supply, a position, and a velocity. Useful for ensuring that velocity and acceleration constraints for a trapezoidal profile are simultaneously achievable - enter the velocity constraint, and this will give you a simultaneously-achievable acceleration constraint.
      Parameters:
      maxVoltage - The maximum voltage that can be supplied to the arm, in volts.
      angle - The angle of the arm, 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.
      velocity - The velocity of the elevator, in (rad/s)
      Returns:
      The maximum possible acceleration in (rad/s²) at the given velocity.
    • minAchievableAcceleration

      public double minAchievableAcceleration(double maxVoltage, double angle, double velocity)
      Calculates the minimum achievable acceleration given a maximum voltage supply, a position, and a velocity. Useful for ensuring that velocity and acceleration constraints for a trapezoidal profile are simultaneously achievable - enter the velocity constraint, and this will give you a simultaneously-achievable acceleration constraint.
      Parameters:
      maxVoltage - The maximum voltage that can be supplied to the arm, in volts.
      angle - The angle of the arm, 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.
      velocity - The velocity of the elevator, in (rad/s)
      Returns:
      The maximum possible acceleration in (rad/s²) at the given velocity.