24 units::meters_per_second_t frontLeft = 0_mps;
29 units::meters_per_second_t frontRight = 0_mps;
34 units::meters_per_second_t rearLeft = 0_mps;
39 units::meters_per_second_t rearRight = 0_mps;
55 units::meters_per_second_t attainableMaxSpeed)
const {
56 std::array<units::meters_per_second_t, 4> wheelSpeeds{frontLeft, frontRight,
59 *std::max_element(wheelSpeeds.begin(), wheelSpeeds.end(),
60 [](
const auto& a,
const auto& b) {
61 return units::math::abs(a) < units::math::abs(b);
64 if (realMaxSpeed > attainableMaxSpeed) {
65 for (
int i = 0; i < 4; ++i) {
66 wheelSpeeds[i] = wheelSpeeds[i] / realMaxSpeed * attainableMaxSpeed;
69 wheelSpeeds[2], wheelSpeeds[3]};
87 return {frontLeft + other.frontLeft, frontRight + other.frontRight,
88 rearLeft + other.rearLeft, rearRight + other.rearRight};
104 return *
this + -other;
115 return {-frontLeft, -frontRight, -rearLeft, -rearRight};
144 return operator*(1.0 /
scalar);
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
Definition SystemServer.h:9
Represents the wheel speeds for a mecanum drive drivetrain.
Definition MecanumDriveWheelSpeeds.h:20
constexpr MecanumDriveWheelSpeeds operator-(const MecanumDriveWheelSpeeds &other) const
Subtracts the other MecanumDriveWheelSpeeds from the current MecanumDriveWheelSpeeds and returns the ...
Definition MecanumDriveWheelSpeeds.h:102
constexpr MecanumDriveWheelSpeeds operator/(double scalar) const
Divides the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.
Definition MecanumDriveWheelSpeeds.h:143
constexpr MecanumDriveWheelSpeeds operator*(double scalar) const
Multiplies the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.
Definition MecanumDriveWheelSpeeds.h:128
constexpr MecanumDriveWheelSpeeds operator-() const
Returns the inverse of the current MecanumDriveWheelSpeeds.
Definition MecanumDriveWheelSpeeds.h:114
constexpr MecanumDriveWheelSpeeds Desaturate(units::meters_per_second_t attainableMaxSpeed) const
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
Definition MecanumDriveWheelSpeeds.h:54
constexpr MecanumDriveWheelSpeeds operator+(const MecanumDriveWheelSpeeds &other) const
Adds two MecanumDriveWheelSpeeds and returns the sum.
Definition MecanumDriveWheelSpeeds.h:85
Type representing an arbitrary unit.
Definition base.h:888