Record Class DriveFeedforwards

java.lang.Object
java.lang.Record
com.pathplanner.lib.util.DriveFeedforwards
Record Components:
accelerationsMPSSq - Linear acceleration at the wheels in meters per second
linearForcesNewtons - Linear force applied by the motors at the wheels in newtons
torqueCurrentsAmps - Torque-current of the drive motors in amps
robotRelativeForcesXNewtons - X components of robot-relative force vectors for the wheels in newtons. The magnitude of these vectors will typically be greater than the linear force feedforwards due to friction forces.
robotRelativeForcesYNewtons - X components of robot-relative force vectors for the wheels in newtons. The magnitude of these vectors will typically be greater than the linear force feedforwards due to friction forces.
All Implemented Interfaces:
Interpolatable<DriveFeedforwards>

public record DriveFeedforwards(double[] accelerationsMPSSq, double[] linearForcesNewtons, double[] torqueCurrentsAmps, double[] robotRelativeForcesXNewtons, double[] robotRelativeForcesYNewtons) extends Record implements Interpolatable<DriveFeedforwards>
Collection of different feedforward values for each drive module. If using swerve, these values will all be in FL, FR, BL, BR order. If using a differential drive, these will be in L, R order.

NOTE: If using Choreo paths, all feedforwards but the X and Y component arrays will be filled with zeros.

  • Constructor Details

    • DriveFeedforwards

      public DriveFeedforwards(edu.wpi.first.units.measure.LinearAcceleration[] accelerations, edu.wpi.first.units.measure.Force[] linearForces, edu.wpi.first.units.measure.Current[] torqueCurrents, edu.wpi.first.units.measure.Force[] robotRelativeForcesX, edu.wpi.first.units.measure.Force[] robotRelativeForcesY)
      Collection of different feedforward values for each drive module. If using swerve, these values will all be in FL, FR, BL, BR order. If using a differential drive, these will be in L, R order.

      NOTE: If using Choreo paths, all feedforwards but the X and Y component arrays will be filled with zeros.

      Parameters:
      accelerations - Linear acceleration at the wheels
      linearForces - Linear force applied by the motors at the wheels
      torqueCurrents - Torque-current of the drive motors
      robotRelativeForcesX - X components of robot-relative force vectors for the wheels. The magnitude of these vectors will typically be greater than the linear force feedforwards due to friction forces.
      robotRelativeForcesY - X components of robot-relative force vectors for the wheels. The magnitude of these vectors will typically be greater than the linear force feedforwards due to friction forces.
    • DriveFeedforwards

      public DriveFeedforwards(double[] accelerationsMPSSq, double[] linearForcesNewtons, double[] torqueCurrentsAmps, double[] robotRelativeForcesXNewtons, double[] robotRelativeForcesYNewtons)
      Creates an instance of a DriveFeedforwards record class.
      Parameters:
      accelerationsMPSSq - the value for the accelerationsMPSSq record component
      linearForcesNewtons - the value for the linearForcesNewtons record component
      torqueCurrentsAmps - the value for the torqueCurrentsAmps record component
      robotRelativeForcesXNewtons - the value for the robotRelativeForcesXNewtons record component
      robotRelativeForcesYNewtons - the value for the robotRelativeForcesYNewtons record component
  • Method Details

    • zeros

      public static DriveFeedforwards zeros(int numModules)
      Create drive feedforwards consisting of all zeros
      Parameters:
      numModules - Number of drive modules
      Returns:
      Zero feedforwards
    • interpolate

      public DriveFeedforwards interpolate(DriveFeedforwards endValue, double t)
      Specified by:
      interpolate in interface Interpolatable<DriveFeedforwards>
    • reverse

      public DriveFeedforwards reverse()
      Reverse the feedforwards for driving backwards. This should only be used for differential drive robots.
      Returns:
      Reversed feedforwards
    • flip

      public DriveFeedforwards flip()
      Flip the feedforwards for the other side of the field. Only does anything if mirrored symmetry is used
      Returns:
      Flipped feedforwards
    • accelerations

      public edu.wpi.first.units.measure.LinearAcceleration[] accelerations()
      Get the linear accelerations at the wheels
      Returns:
      Linear accelerations at the wheels
    • linearForces

      public edu.wpi.first.units.measure.Force[] linearForces()
      Get the linear forces at the wheels
      Returns:
      Linear forces at the wheels
    • torqueCurrents

      public edu.wpi.first.units.measure.Current[] torqueCurrents()
      Get the torque-current of the drive motors
      Returns:
      Torque-current of the drive motors
    • robotRelativeForcesX

      public edu.wpi.first.units.measure.Force[] robotRelativeForcesX()
      Get the X components of the robot-relative force vectors at the wheels
      Returns:
      X components of the robot-relative force vectors at the wheels
    • robotRelativeForcesY

      public edu.wpi.first.units.measure.Force[] robotRelativeForcesY()
      Get the Y components of the robot-relative force vectors at the wheels
      Returns:
      Y components of the robot-relative force vectors at the wheels
    • toString

      public final String toString()
      Returns a string representation of this record class. The representation contains the name of the class, followed by the name and value of each of the record components.
      Specified by:
      toString in class Record
      Returns:
      a string representation of this object
    • hashCode

      public final int hashCode()
      Returns a hash code value for this object. The value is derived from the hash code of each of the record components.
      Specified by:
      hashCode in class Record
      Returns:
      a hash code value for this object
    • equals

      public final boolean equals(Object o)
      Indicates whether some other object is "equal to" this one. The objects are equal if the other object is of the same class and if all the record components are equal. All components in this record class are compared with Objects::equals(Object,Object).
      Specified by:
      equals in class Record
      Parameters:
      o - the object with which to compare
      Returns:
      true if this object is the same as the o argument; false otherwise.
    • accelerationsMPSSq

      public double[] accelerationsMPSSq()
      Returns the value of the accelerationsMPSSq record component.
      Returns:
      the value of the accelerationsMPSSq record component
    • linearForcesNewtons

      public double[] linearForcesNewtons()
      Returns the value of the linearForcesNewtons record component.
      Returns:
      the value of the linearForcesNewtons record component
    • torqueCurrentsAmps

      public double[] torqueCurrentsAmps()
      Returns the value of the torqueCurrentsAmps record component.
      Returns:
      the value of the torqueCurrentsAmps record component
    • robotRelativeForcesXNewtons

      public double[] robotRelativeForcesXNewtons()
      Returns the value of the robotRelativeForcesXNewtons record component.
      Returns:
      the value of the robotRelativeForcesXNewtons record component
    • robotRelativeForcesYNewtons

      public double[] robotRelativeForcesYNewtons()
      Returns the value of the robotRelativeForcesYNewtons record component.
      Returns:
      the value of the robotRelativeForcesYNewtons record component