19 units::meters_per_second_t left = 0_mps;
24 units::meters_per_second_t right = 0_mps;
38 void Desaturate(units::meters_per_second_t attainableMaxSpeed);
53 return {left + other.
left, right + other.
right};
70 return *
this + -other;
81 return {-left, -right};
#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 differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:15
constexpr DifferentialDriveWheelSpeeds operator+(const DifferentialDriveWheelSpeeds &other) const
Adds two DifferentialDriveWheelSpeeds and returns the sum.
Definition: DifferentialDriveWheelSpeeds.h:51
units::meters_per_second_t left
Speed of the left side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:19
void Desaturate(units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if either side is above the specified maximum.
constexpr DifferentialDriveWheelSpeeds operator*(double scalar) const
Multiplies the DifferentialDriveWheelSpeeds by a scalar and returns the new DifferentialDriveWheelSpe...
Definition: DifferentialDriveWheelSpeeds.h:95
constexpr DifferentialDriveWheelSpeeds operator/(double scalar) const
Divides the DifferentialDriveWheelSpeeds by a scalar and returns the new DifferentialDriveWheelSpeeds...
Definition: DifferentialDriveWheelSpeeds.h:110
constexpr DifferentialDriveWheelSpeeds operator-() const
Returns the inverse of the current DifferentialDriveWheelSpeeds.
Definition: DifferentialDriveWheelSpeeds.h:80
constexpr DifferentialDriveWheelSpeeds operator-(const DifferentialDriveWheelSpeeds &other) const
Subtracts the other DifferentialDriveWheelSpeeds from the current DifferentialDriveWheelSpeeds and re...
Definition: DifferentialDriveWheelSpeeds.h:68
units::meters_per_second_t right
Speed of the right side of the robot.
Definition: DifferentialDriveWheelSpeeds.h:24