Package choreo.trajectory
Class SwerveSample
java.lang.Object
choreo.trajectory.SwerveSample
- All Implemented Interfaces:
TrajectorySample<SwerveSample>
,Interpolatable<SwerveSample>
,StructSerializable
,WPISerializable
A single swerve robot sample in a Trajectory.
-
Field Summary
Modifier and TypeFieldDescriptionfinal double
The angular acceleration of the sample in rad/s².final double
The acceleration of the in the X direction in m/s².final double
The acceleration of the 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
ConstructorDescriptionSwerveSample
(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 TypeMethodDescriptionboolean
flipped()
Returns this sample, mirrored across the field midline.Returns the field-relative chassis speeds of this sample.getPose()
Returns the pose at this sample.double
Returns the timestamp of this sample.interpolate
(SwerveSample endValue, double timestamp) makeArray
(int length) For internal use only.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.
-
Field Details
-
t
The timestamp of this sample, relative to the beginning of the trajectory. -
x
The X position of the sample relative to the blue alliance wall origin in meters. -
y
The Y position of the sample relative to the blue alliance wall origin 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 in the X direction in m/s². -
ay
The acceleration of the in the Y direction in m/s². -
alpha
The angular acceleration of the sample in rad/s². -
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
-
moduleForcesX
A null safe getter for the module forces in the X direction.- Returns:
- The module forces in the X direction.
-
moduleForcesY
A null safe getter for the module forces in the Y direction.- Returns:
- The module forces in the Y direction.
-
getTimestamp
Description copied from interface:TrajectorySample
Returns the timestamp of this sample.- Specified by:
getTimestamp
in interfaceTrajectorySample<SwerveSample>
- Returns:
- the timestamp of this sample.
-
getPose
Description copied from interface:TrajectorySample
Returns the pose at this sample.- Specified by:
getPose
in interfaceTrajectorySample<SwerveSample>
- Returns:
- the pose at this sample.
-
getChassisSpeeds
Description copied from interface:TrajectorySample
Returns the field-relative chassis speeds of this sample.- Specified by:
getChassisSpeeds
in interfaceTrajectorySample<SwerveSample>
- Returns:
- the field-relative chassis speeds of this sample.
-
interpolate
- Specified by:
interpolate
in interfaceInterpolatable<SwerveSample>
-
offsetBy
Description copied from interface:TrajectorySample
Returns this sample, offset by the given timestamp.- Specified by:
offsetBy
in interfaceTrajectorySample<SwerveSample>
- Parameters:
timestampOffset
- the offset to apply to the timestamp.- Returns:
- this sample, offset by the given timestamp.
-
flipped
Description copied from interface:TrajectorySample
Returns this sample, mirrored across the field midline.- Specified by:
flipped
in interfaceTrajectorySample<SwerveSample>
- Returns:
- this sample, mirrored across the field midline.
-
makeArray
Description copied from interface:TrajectorySample
For internal use only.- Specified by:
makeArray
in interfaceTrajectorySample<SwerveSample>
- Parameters:
length
- the length of the array to create.- Returns:
- the created array.
-
equals
-