8#include "wpi/units/angle.hpp"
9#include "wpi/units/math.hpp"
10#include "wpi/units/velocity.hpp"
21 wpi::units::meters_per_second_t
velocity = 0_mps;
50 auto delta =
angle - currentAngle;
51 if (wpi::units::math::abs(delta.Degrees()) > 90_deg) {
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:29
Definition LinearSystem.hpp:20
Represents the velocity of one swerve module.
Definition SwerveModuleVelocity.hpp:17
constexpr SwerveModuleVelocity Optimize(const Rotation2d ¤tAngle)
Minimize the change in the heading this swerve module velocity would require by potentially reversing...
Definition SwerveModuleVelocity.hpp:49
wpi::units::meters_per_second_t velocity
Velocity of the wheel of the module.
Definition SwerveModuleVelocity.hpp:21
Rotation2d angle
Angle of the module.
Definition SwerveModuleVelocity.hpp:26
constexpr SwerveModuleVelocity CosineScale(const Rotation2d ¤tAngle)
Scales velocity by cosine of angle error.
Definition SwerveModuleVelocity.hpp:67
constexpr bool operator==(const SwerveModuleVelocity &other) const
Checks equality between this SwerveModuleVelocity and another object.
Definition SwerveModuleVelocity.hpp:34