8#include "wpi/units/length.hpp"
9#include "wpi/units/math.hpp"
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Definition LinearSystem.hpp:20
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition MathExtras.hpp:780
Represents the position of one swerve module.
Definition SwerveModulePosition.hpp:17
constexpr bool operator==(const SwerveModulePosition &other) const
Checks equality between this SwerveModulePosition and another object.
Definition SwerveModulePosition.hpp:34
wpi::units::meter_t distance
Distance the wheel of a module has traveled.
Definition SwerveModulePosition.hpp:21
constexpr SwerveModulePosition Interpolate(const SwerveModulePosition &endValue, double t) const
Definition SwerveModulePosition.hpp:39
Rotation2d angle
Angle of the module.
Definition SwerveModulePosition.hpp:26