![]() |
WPILibC++ 2027.0.0-alpha-4
|
Represents the position of one swerve module. More...
#include <wpi/math/kinematics/SwerveModulePosition.hpp>
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 | |
| wpi::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 wpi::math::SwerveModulePosition::angle |
Angle of the module.
| wpi::units::meter_t wpi::math::SwerveModulePosition::distance = 0_m |
Distance the wheel of a module has traveled.