22 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:31
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition MathExtras.h:772
Represents the position of one swerve module.
Definition SwerveModulePosition.h:18
constexpr SwerveModulePosition Interpolate(const SwerveModulePosition &endValue, double t) const
Definition SwerveModulePosition.h:40
units::meter_t distance
Distance the wheel of a module has traveled.
Definition SwerveModulePosition.h:22
constexpr bool operator==(const SwerveModulePosition &other) const
Checks equality between this SwerveModulePosition and another object.
Definition SwerveModulePosition.h:35
Rotation2d angle
Angle of the module.
Definition SwerveModulePosition.h:27