WPILibC++ 2024.3.2
|
Represents the position of one swerve module. More...
#include <frc/kinematics/SwerveModulePosition.h>
Public Member Functions | |
bool | operator== (const SwerveModulePosition &other) const |
Checks equality between this SwerveModulePosition and another object. More... | |
SwerveModulePosition | Interpolate (const SwerveModulePosition &endValue, double t) const |
Public Attributes | |
units::meter_t | distance = 0_m |
Distance the wheel of a module has traveled. More... | |
Rotation2d | angle |
Angle of the module. More... | |
Represents the position of one swerve module.
|
inline |
bool frc::SwerveModulePosition::operator== | ( | const SwerveModulePosition & | other | ) | const |
Checks equality between this SwerveModulePosition and another object.
other | The other object. |
Rotation2d frc::SwerveModulePosition::angle |
Angle of the module.
units::meter_t frc::SwerveModulePosition::distance = 0_m |
Distance the wheel of a module has traveled.