19 units::meters_per_second_t frontLeft = 0_mps;
24 units::meters_per_second_t frontRight = 0_mps;
29 units::meters_per_second_t rearLeft = 0_mps;
34 units::meters_per_second_t rearRight = 0_mps;
48 void Desaturate(units::meters_per_second_t attainableMaxSpeed);
79 return *
this + -other;
90 return {-frontLeft, -frontRight, -rearLeft, -rearRight};
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Definition: AprilTagPoseEstimator.h:15
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelSpeeds.h:15
constexpr MecanumDriveWheelSpeeds operator-(const MecanumDriveWheelSpeeds &other) const
Subtracts the other MecanumDriveWheelSpeeds from the current MecanumDriveWheelSpeeds and returns the ...
Definition: MecanumDriveWheelSpeeds.h:77
constexpr MecanumDriveWheelSpeeds operator/(double scalar) const
Divides the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.
Definition: MecanumDriveWheelSpeeds.h:118
constexpr MecanumDriveWheelSpeeds operator*(double scalar) const
Multiplies the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.
Definition: MecanumDriveWheelSpeeds.h:103
units::meters_per_second_t frontRight
Speed of the front-right wheel.
Definition: MecanumDriveWheelSpeeds.h:24
constexpr MecanumDriveWheelSpeeds operator-() const
Returns the inverse of the current MecanumDriveWheelSpeeds.
Definition: MecanumDriveWheelSpeeds.h:89
void Desaturate(units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
units::meters_per_second_t frontLeft
Speed of the front-left wheel.
Definition: MecanumDriveWheelSpeeds.h:19
units::meters_per_second_t rearRight
Speed of the rear-right wheel.
Definition: MecanumDriveWheelSpeeds.h:34
units::meters_per_second_t rearLeft
Speed of the rear-left wheel.
Definition: MecanumDriveWheelSpeeds.h:29
constexpr MecanumDriveWheelSpeeds operator+(const MecanumDriveWheelSpeeds &other) const
Adds two MecanumDriveWheelSpeeds and returns the sum.
Definition: MecanumDriveWheelSpeeds.h:60