Class SimpleMotorFeedforward

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

public class SimpleMotorFeedforward
extends Object
A helper class that computes feedforward outputs for a simple permanent-magnet DC motor.
  • Field Summary

    Fields 
    Modifier and Type Field Description
    double ka  
    double ks  
    double kv  
  • Constructor Summary

    Constructors 
    Constructor Description
    SimpleMotorFeedforward​(double ks, double kv)
    Creates a new SimpleMotorFeedforward with the specified gains.
    SimpleMotorFeedforward​(double ks, double kv, double ka)
    Creates a new SimpleMotorFeedforward with the specified gains.
  • Method Summary

    Modifier and Type Method Description
    double calculate​(double velocity)
    Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be zero).
    double calculate​(double velocity, double acceleration)
    Calculates the feedforward from the gains and setpoints.
    double calculate​(double currentVelocity, double nextVelocity, double dtSeconds)
    Calculates the feedforward from the gains and setpoints.
    double maxAchievableAcceleration​(double maxVoltage, double velocity)
    Calculates the maximum achievable acceleration given a maximum voltage supply and a velocity.
    double maxAchievableVelocity​(double maxVoltage, double acceleration)
    Calculates the maximum achievable velocity given a maximum voltage supply and an acceleration.
    double minAchievableAcceleration​(double maxVoltage, double velocity)
    Calculates the minimum achievable acceleration given a maximum voltage supply and a velocity.
    double minAchievableVelocity​(double maxVoltage, double acceleration)
    Calculates the minimum achievable velocity given a maximum voltage supply 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
    • kv

      public final double kv
    • ka

      public final double ka
  • Constructor Details

    • SimpleMotorFeedforward

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

      public SimpleMotorFeedforward​(double ks, double kv)
      Creates a new SimpleMotorFeedforward 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.
      kv - The velocity gain.
  • Method Details

    • calculate

      public double calculate​(double velocity, double acceleration)
      Calculates the feedforward from the gains and setpoints.
      Parameters:
      velocity - The velocity setpoint.
      acceleration - The acceleration setpoint.
      Returns:
      The computed feedforward.
    • calculate

      public double calculate​(double currentVelocity, double nextVelocity, double dtSeconds)
      Calculates the feedforward from the gains and setpoints.
      Parameters:
      currentVelocity - The current velocity setpoint.
      nextVelocity - The next velocity setpoint.
      dtSeconds - Time between velocity setpoints in seconds.
      Returns:
      The computed feedforward.
    • calculate

      public double calculate​(double velocity)
      Calculates the feedforward from the gains and velocity setpoint (acceleration is assumed to be zero).
      Parameters:
      velocity - The velocity setpoint.
      Returns:
      The computed feedforward.
    • maxAchievableVelocity

      public double maxAchievableVelocity​(double maxVoltage, double acceleration)
      Calculates the maximum achievable velocity given a maximum voltage supply 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 motor.
      acceleration - The acceleration of the motor.
      Returns:
      The maximum possible velocity at the given acceleration.
    • minAchievableVelocity

      public double minAchievableVelocity​(double maxVoltage, double acceleration)
      Calculates the minimum achievable velocity given a maximum voltage supply 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 motor.
      acceleration - The acceleration of the motor.
      Returns:
      The minimum possible velocity at the given acceleration.
    • maxAchievableAcceleration

      public double maxAchievableAcceleration​(double maxVoltage, double velocity)
      Calculates the maximum achievable acceleration given a maximum voltage supply 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 motor.
      velocity - The velocity of the motor.
      Returns:
      The maximum possible acceleration at the given velocity.
    • minAchievableAcceleration

      public double minAchievableAcceleration​(double maxVoltage, double velocity)
      Calculates the minimum achievable acceleration given a maximum voltage supply 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 motor.
      velocity - The velocity of the motor.
      Returns:
      The minimum possible acceleration at the given velocity.