WPILibC++ 2024.3.2
|
Represents the state of one swerve module. More...
#include <frc/kinematics/SwerveModuleState.h>
Public Member Functions | |
bool | operator== (const SwerveModuleState &other) const |
Checks equality between this SwerveModuleState and another object. More... | |
Static Public Member Functions | |
static SwerveModuleState | Optimize (const SwerveModuleState &desiredState, const Rotation2d ¤tAngle) |
Minimize the change in heading the desired swerve module state would require by potentially reversing the direction the wheel spins. More... | |
Public Attributes | |
units::meters_per_second_t | speed = 0_mps |
Speed of the wheel of the module. More... | |
Rotation2d | angle |
Angle of the module. More... | |
Represents the state of one swerve module.
bool frc::SwerveModuleState::operator== | ( | const SwerveModuleState & | other | ) | const |
Checks equality between this SwerveModuleState and another object.
other | The other object. |
|
static |
Minimize the change in heading the desired swerve module state would require by potentially reversing the direction the wheel spins.
If this is used with the PIDController class's continuous input functionality, the furthest a wheel will ever rotate is 90 degrees.
desiredState | The desired state. |
currentAngle | The current module angle. |
Rotation2d frc::SwerveModuleState::angle |
Angle of the module.
units::meters_per_second_t frc::SwerveModuleState::speed = 0_mps |
Speed of the wheel of the module.