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