23 units::meter_t distance = 0_m;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Definition: AprilTagPoseEstimator.h:15
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition: MathExtras.h:638
Represents the position of one swerve module.
Definition: SwerveModulePosition.h:19
bool operator==(const SwerveModulePosition &other) const
Checks equality between this SwerveModulePosition and another object.
units::meter_t distance
Distance the wheel of a module has traveled.
Definition: SwerveModulePosition.h:23
SwerveModulePosition Interpolate(const SwerveModulePosition &endValue, double t) const
Definition: SwerveModulePosition.h:38
Rotation2d angle
Angle of the module.
Definition: SwerveModulePosition.h:28