Record Class SimulationConstants.Offsets

java.lang.Object
java.lang.Record
com.stuypulse.robot.util.simulation.SimulationConstants.Offsets
Record Components:
x - X translation from the robot origin (meters)
y - Y translation from the robot origin (meters)
z - Z translation from the robot origin (meters)
roll - Rotation about the X axis
pitch - Rotation about the Y axis
yaw - Rotation about the Z axis
Enclosing interface:
SimulationConstants

public static record SimulationConstants.Offsets(edu.wpi.first.units.measure.Distance x, edu.wpi.first.units.measure.Distance y, edu.wpi.first.units.measure.Distance z, edu.wpi.first.units.measure.Angle roll, edu.wpi.first.units.measure.Angle pitch, edu.wpi.first.units.measure.Angle yaw) extends Record

Record that holds CAD Offsets

Sourced from CAD exports to hold a component's positional offsets from their position in CAD to their position in sim


 Offsets SHOOTER = new Offsets(-0.1016, 0.2032, 0.3255,
     Degrees.of(90), Degrees.of(0), Degrees.of(-90));

 Pose3d shooterPose = SHOOTER.withRotation(
     new Rotation3d(0, 0, turretSim.getAngle().getRadians())
 );
 
  • Constructor Summary

    Constructors
    Constructor
    Description
    Offsets(double x, double y, double z)
    Constructs an Offsets instance with no rotation
    Offsets(double x, double y, double z, edu.wpi.first.units.measure.Angle roll, edu.wpi.first.units.measure.Angle pitch, edu.wpi.first.units.measure.Angle yaw)
    Constructs an Offsets instance with no rotation
    Offsets(edu.wpi.first.units.measure.Angle roll, edu.wpi.first.units.measure.Angle pitch, edu.wpi.first.units.measure.Angle yaw)
    Constructs an Offsets instance with no translation
    Offsets(edu.wpi.first.units.measure.Distance x, edu.wpi.first.units.measure.Distance y, edu.wpi.first.units.measure.Distance z)
    Constructs an Offsets instance with no rotation, using your unit of choice
    Offsets(edu.wpi.first.units.measure.Distance x, edu.wpi.first.units.measure.Distance y, edu.wpi.first.units.measure.Distance z, edu.wpi.first.units.measure.Angle roll, edu.wpi.first.units.measure.Angle pitch, edu.wpi.first.units.measure.Angle yaw)
    Creates an instance of a Offsets record class.
  • Method Summary

    Modifier and Type
    Method
    Description
    edu.wpi.first.math.geometry.Pose2d
    applyToPose2d(edu.wpi.first.math.geometry.Pose2d pose)
    Applies this offset's X/Y translation and yaw onto an existing Pose2d
    edu.wpi.first.math.geometry.Pose2d
    applyToPose2dRobotRelative(edu.wpi.first.math.geometry.Pose2d pose)
    Applies this offset's X/Y translation and yaw onto an existing Pose2d
    edu.wpi.first.math.geometry.Pose3d
    applyToPose3d(edu.wpi.first.math.geometry.Pose3d pose)
    Applies this offset's translation and rotation onto an existing Pose3d
    edu.wpi.first.math.geometry.Pose3d
    applyToPose3dRobotRelative(edu.wpi.first.math.geometry.Pose3d pose)
    Applies this offset's translation and rotation onto an existing Pose3d
    edu.wpi.first.math.geometry.Rotation2d
    applyToRotation2d(edu.wpi.first.math.geometry.Rotation2d rotation)
    Applies this offset's yaw onto an existing Rotation2d
    edu.wpi.first.math.geometry.Rotation3d
    applyToRotation3d(edu.wpi.first.math.geometry.Rotation3d rotation)
    Composes this offset's rotation onto an existing Rotation3d
    final boolean
    Indicates whether some other object is "equal to" this one.
    final int
    Returns a hash code value for this object.
    edu.wpi.first.units.measure.Angle
    Returns the value of the pitch record component.
    edu.wpi.first.units.measure.Angle
    Returns the value of the roll record component.
    edu.wpi.first.math.geometry.Pose3d
    This offset as a Pose3d.
    edu.wpi.first.math.geometry.Rotation3d
    Rotational component as a Rotation3d
    final String
    Returns a string representation of this record class.
    edu.wpi.first.math.geometry.Translation3d
    Translational component as a Translation3d
    edu.wpi.first.math.geometry.Pose3d
    withRotation(edu.wpi.first.math.geometry.Rotation3d rotation)
    Pose at this offset's translation with an additional rotation
    edu.wpi.first.units.measure.Distance
    x()
    Returns the value of the x record component.
    edu.wpi.first.units.measure.Distance
    y()
    Returns the value of the y record component.
    edu.wpi.first.units.measure.Angle
    yaw()
    Returns the value of the yaw record component.
    edu.wpi.first.units.measure.Distance
    z()
    Returns the value of the z record component.

    Methods inherited from class java.lang.Object

    clone, finalize, getClass, notify, notifyAll, wait, wait, wait
  • Constructor Details

    • Offsets

      public Offsets(double x, double y, double z)

      Constructs an Offsets instance with no rotation

      Parameters:
      x - X translation from the robot origin (meters)
      y - Y translation from the robot origin (meters)
      z - Z translation from the robot origin (meters)
    • Offsets

      public Offsets(edu.wpi.first.units.measure.Distance x, edu.wpi.first.units.measure.Distance y, edu.wpi.first.units.measure.Distance z)

      Constructs an Offsets instance with no rotation, using your unit of choice

      Parameters:
      x - X translation from the robot origin
      y - Y translation from the robot origin
      z - Z translation from the robot origin
    • Offsets

      public Offsets(edu.wpi.first.units.measure.Angle roll, edu.wpi.first.units.measure.Angle pitch, edu.wpi.first.units.measure.Angle yaw)

      Constructs an Offsets instance with no translation

      Parameters:
      roll - Rotation about the X axis
      pitch - Rotation about the Y axis
      yaw - Rotation about the Z axis
    • Offsets

      public Offsets(double x, double y, double z, edu.wpi.first.units.measure.Angle roll, edu.wpi.first.units.measure.Angle pitch, edu.wpi.first.units.measure.Angle yaw)

      Constructs an Offsets instance with no rotation

      Parameters:
      x - X translation from the robot origin (meters)
      y - Y translation from the robot origin (meters)
      z - Z translation from the robot origin (meters)
      roll - Rotation about the X axis
      pitch - Rotation about the Y axis
      yaw - Rotation about the Z axis
    • Offsets

      public Offsets(edu.wpi.first.units.measure.Distance x, edu.wpi.first.units.measure.Distance y, edu.wpi.first.units.measure.Distance z, edu.wpi.first.units.measure.Angle roll, edu.wpi.first.units.measure.Angle pitch, edu.wpi.first.units.measure.Angle yaw)
      Creates an instance of a Offsets record class.
      Parameters:
      x - the value for the x record component
      y - the value for the y record component
      z - the value for the z record component
      roll - the value for the roll record component
      pitch - the value for the pitch record component
      yaw - the value for the yaw record component
  • Method Details

    • toTranslation3d

      public edu.wpi.first.math.geometry.Translation3d toTranslation3d()

      Translational component as a Translation3d

      Returns:
      translation from the robot origin
    • toRotation3d

      public edu.wpi.first.math.geometry.Rotation3d toRotation3d()

      Rotational component as a Rotation3d

      Returns:
      Rotation3d of the roll, pitch, and yaw components of the offset
    • toPose3d

      public edu.wpi.first.math.geometry.Pose3d toPose3d()

      This offset as a Pose3d.

      Useful for components whose pose is fully static and requires no adjustments

      Returns:
      pose at this offset's position and orientation
    • applyToPose3d

      public edu.wpi.first.math.geometry.Pose3d applyToPose3d(edu.wpi.first.math.geometry.Pose3d pose)

      Applies this offset's translation and rotation onto an existing Pose3d

      Parameters:
      pose - the base pose to offset
      Returns:
      a new pose with this offset applied to both translation and rotation
    • applyToPose3dRobotRelative

      public edu.wpi.first.math.geometry.Pose3d applyToPose3dRobotRelative(edu.wpi.first.math.geometry.Pose3d pose)

      Applies this offset's translation and rotation onto an existing Pose3d

      Translation is applied, but it is robot robot relative

      Parameters:
      pose - the base pose to offset
      Returns:
      a new pose with this offset applied to both translation and rotation
    • applyToRotation3d

      public edu.wpi.first.math.geometry.Rotation3d applyToRotation3d(edu.wpi.first.math.geometry.Rotation3d rotation)

      Composes this offset's rotation onto an existing Rotation3d

      Parameters:
      rotation - the base rotation to offset
      Returns:
      a new rotation with this offset's rotation applied on top
    • withRotation

      public edu.wpi.first.math.geometry.Pose3d withRotation(edu.wpi.first.math.geometry.Rotation3d rotation)

      Pose at this offset's translation with an additional rotation

      Applies a rotation to this offsets rotation

      
       SHOOTER_OFFSETS.withRotation(
           new Rotation3d(0, 0, turretSim.getAngle().getRadians())
       );
       
      Parameters:
      rotation - the additional rotation to add to this offset's rotation
      Returns:
      a new pose at this offset's translation with the combined rotation
    • applyToPose2d

      public edu.wpi.first.math.geometry.Pose2d applyToPose2d(edu.wpi.first.math.geometry.Pose2d pose)

      Applies this offset's X/Y translation and yaw onto an existing Pose2d

      Roll and pitch are ignored because they have no 2D equivalent

      Parameters:
      pose - the base 2D pose to offset
      Returns:
      a new pose of this offset's X, Y, and yaw
    • applyToPose2dRobotRelative

      public edu.wpi.first.math.geometry.Pose2d applyToPose2dRobotRelative(edu.wpi.first.math.geometry.Pose2d pose)

      Applies this offset's X/Y translation and yaw onto an existing Pose2d

      Translation is applied, but it is robot robot relative

      Parameters:
      pose - the base 2D pose to offset
      Returns:
      a new pose with this offset applied
    • applyToRotation2d

      public edu.wpi.first.math.geometry.Rotation2d applyToRotation2d(edu.wpi.first.math.geometry.Rotation2d rotation)

      Applies this offset's yaw onto an existing Rotation2d

      Roll and pitch are ignored because they have no 2D equivalent

      Parameters:
      rotation - the base 2D rotation to offset
      Returns:
      a new rotation with this offset's yaw applied on top
    • 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.
    • x

      public edu.wpi.first.units.measure.Distance x()
      Returns the value of the x record component.
      Returns:
      the value of the x record component
    • y

      public edu.wpi.first.units.measure.Distance y()
      Returns the value of the y record component.
      Returns:
      the value of the y record component
    • z

      public edu.wpi.first.units.measure.Distance z()
      Returns the value of the z record component.
      Returns:
      the value of the z record component
    • roll

      public edu.wpi.first.units.measure.Angle roll()
      Returns the value of the roll record component.
      Returns:
      the value of the roll record component
    • pitch

      public edu.wpi.first.units.measure.Angle pitch()
      Returns the value of the pitch record component.
      Returns:
      the value of the pitch record component
    • yaw

      public edu.wpi.first.units.measure.Angle yaw()
      Returns the value of the yaw record component.
      Returns:
      the value of the yaw record component