Class SwerveSample

java.lang.Object
choreo.trajectory.SwerveSample
All Implemented Interfaces:
TrajectorySample<SwerveSample>, Interpolatable<SwerveSample>, StructSerializable, WPISerializable

public class SwerveSample extends Object implements TrajectorySample<SwerveSample>
A single swerve robot sample in a Trajectory.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final double
    The angular acceleration of the sample in rad/s².
    final double
    The acceleration of the sample in the X direction in m/s².
    final double
    The acceleration of the sample in the Y direction in m/s².
    final double
    The heading of the sample in radians, with 0 being in the +X direction.
    final double
    The angular velocity of the sample in rad/s.
    static final Struct<SwerveSample>
    The struct for the SwerveSample class.
    final double
    The timestamp of this sample, relative to the beginning of the trajectory.
    final double
    The velocity of the sample in the X direction in m/s.
    final double
    The velocity of the sample in the Y direction in m/s.
    final double
    The X position of the sample relative to the blue alliance wall origin in meters.
    final double
    The Y position of the sample relative to the blue alliance wall origin in meters.
  • Constructor Summary

    Constructors
    Constructor
    Description
    SwerveSample(double t, double x, double y, double heading, double vx, double vy, double omega, double ax, double ay, double alpha, double[] moduleForcesX, double[] moduleForcesY)
    Constructs a SwerveSample with the specified parameters.
  • Method Summary

    Modifier and Type
    Method
    Description
    boolean
     
    Returns this sample, flipped to the other alliance according to the symmetry of the field.
    Returns the field-relative chassis speeds of this sample.
    Returns the pose at this sample.
    double
    Returns the timestamp of this sample.
    interpolate(SwerveSample endValue, double timestamp)
     
    Returns this sample, mirrored to the other alliance.
    Returns this sample, mirrored left-to-right from the driver's perspective.
    double[]
    A null safe getter for the module forces in the X direction.
    double[]
    A null safe getter for the module forces in the Y direction.
    offsetBy(double timestampOffset)
    Returns this sample, offset by the given timestamp.
    Returns this sample, rotated 180 degrees around the field center.

    Methods inherited from class java.lang.Object

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

    • t

      public final double t
      The timestamp of this sample, relative to the beginning of the trajectory.
    • x

      public final double x
      The X position of the sample relative to the blue alliance wall origin in meters.
    • y

      public final double y
      The Y position of the sample relative to the blue alliance wall origin in meters.
    • heading

      public final double heading
      The heading of the sample in radians, with 0 being in the +X direction.
    • vx

      public final double vx
      The velocity of the sample in the X direction in m/s.
    • vy

      public final double vy
      The velocity of the sample in the Y direction in m/s.
    • omega

      public final double omega
      The angular velocity of the sample in rad/s.
    • ax

      public final double ax
      The acceleration of the sample in the X direction in m/s².
    • ay

      public final double ay
      The acceleration of the sample in the Y direction in m/s².
    • alpha

      public final double alpha
      The angular acceleration of the sample in rad/s².
    • struct

      public static final Struct<SwerveSample> struct
      The struct for the SwerveSample class.
  • Constructor Details

    • SwerveSample

      public SwerveSample(double t, double x, double y, double heading, double vx, double vy, double omega, double ax, double ay, double alpha, double[] moduleForcesX, double[] moduleForcesY)
      Constructs a SwerveSample with the specified parameters.
      Parameters:
      t - The timestamp of this sample, relative to the beginning of the trajectory.
      x - The X position of the sample in meters.
      y - The Y position of the sample in meters.
      heading - The heading of the sample in radians, with 0 being in the +X direction.
      vx - The velocity of the sample in the X direction in m/s.
      vy - The velocity of the sample in the Y direction in m/s.
      omega - The angular velocity of the sample in rad/s.
      ax - The acceleration of the sample in the X direction in m/s².
      ay - The acceleration of the sample in the Y direction in m/s².
      alpha - The angular acceleration of the sample in rad/s².
      moduleForcesX - The force on each swerve module in the X direction in Newtons. Module forces appear in the following order: [FL, FR, BL, BR].
      moduleForcesY - The force on each swerve module in the Y direction in Newtons. Module forces appear in the following order: [FL, FR, BL, BR].
  • Method Details