Class ArmFeedforward

java.lang.Object
edu.wpi.first.math.controller.ArmFeedforward

public class ArmFeedforward
extends Object
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
    double ka  
    double kg  
    double ks  
    double kv  
  • 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.
  • Method Summary

    Modifier and Type Method Description
    double calculate​(double positionRadians, double velocity)
    Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be zero).
    double calculate​(double positionRadians, double velocityRadPerSec, double accelRadPerSecSquared)
    Calculates the feedforward from the gains and setpoints.
    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

    • ks

      public final double ks
    • kg

      public final double kg
    • kv

      public final double kv
    • ka

      public final double ka
  • Constructor Details

    • ArmFeedforward

      public ArmFeedforward​(double ks, double kg, double kv, double ka)
      Creates a new ArmFeedforward with the specified gains. Units of the gain values will dictate units of the computed feedforward.
      Parameters:
      ks - The static gain.
      kg - The gravity gain.
      kv - The velocity gain.
      ka - The acceleration gain.
    • ArmFeedforward

      public ArmFeedforward​(double ks, double kg, double kv)
      Creates a new ArmFeedforward with the specified gains. Acceleration gain is defaulted to zero. Units of the gain values will dictate units of the computed feedforward.
      Parameters:
      ks - The static gain.
      kg - The gravity gain.
      kv - The velocity gain.
  • Method Details

    • calculate

      public double calculate​(double positionRadians, double velocityRadPerSec, double accelRadPerSecSquared)
      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 (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.
    • 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. 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.
      Returns:
      The maximum possible velocity 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.
      angle - The angle of the arm. 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.
      Returns:
      The minimum possible velocity 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.
      angle - The angle of the arm. 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 arm.
      Returns:
      The maximum possible acceleration 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.
      angle - The angle of the arm. 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 arm.
      Returns:
      The minimum possible acceleration at the given velocity.