22 units::meters_per_second_t speed = 0_mps;
49 auto delta = angle - currentAngle;
65 [[deprecated(
"Use instance method instead.")]]
68 auto delta = desiredState.
angle - currentAngle;
72 return {desiredState.
speed, desiredState.
angle};
84 speed *= (angle - currentAngle).Cos();
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
Represents the state of one swerve module.
Definition SwerveModuleState.h:18
static constexpr SwerveModuleState Optimize(const SwerveModuleState &desiredState, const Rotation2d ¤tAngle)
Minimize the change in heading the desired swerve module state would require by potentially reversing...
Definition SwerveModuleState.h:66
constexpr void CosineScale(const Rotation2d ¤tAngle)
Scales speed by cosine of angle error.
Definition SwerveModuleState.h:83
units::meters_per_second_t speed
Speed of the wheel of the module.
Definition SwerveModuleState.h:22
Rotation2d angle
Angle of the module.
Definition SwerveModuleState.h:27
constexpr void Optimize(const Rotation2d ¤tAngle)
Minimize the change in the heading this swerve module state would require by potentially reversing th...
Definition SwerveModuleState.h:48
constexpr bool operator==(const SwerveModuleState &other) const
Checks equality between this SwerveModuleState and another object.
Definition SwerveModuleState.h:35