7#include "wpi/units/math.hpp"
8#include "wpi/units/velocity.hpp"
19 wpi::units::meters_per_second_t
left = 0_mps;
24 wpi::units::meters_per_second_t
right = 0_mps;
43 wpi::units::meters_per_second_t attainableMaxVelocity) {
44 auto realMaxVelocity = wpi::units::math::max(wpi::units::math::abs(
left),
45 wpi::units::math::abs(
right));
47 if (realMaxVelocity > attainableMaxVelocity) {
48 return {
left / realMaxVelocity * attainableMaxVelocity,
49 right / realMaxVelocity * attainableMaxVelocity};
82 return *
this + -other;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Definition LinearSystem.hpp:20
Represents the wheel velocities for a differential drive drivetrain.
Definition DifferentialDriveWheelVelocities.hpp:15
constexpr DifferentialDriveWheelVelocities Desaturate(wpi::units::meters_per_second_t attainableMaxVelocity)
Renormalizes the wheel velocities if either side is above the specified maximum.
Definition DifferentialDriveWheelVelocities.hpp:42
constexpr DifferentialDriveWheelVelocities operator-(const DifferentialDriveWheelVelocities &other) const
Subtracts the other DifferentialDriveWheelVelocities from the current DifferentialDriveWheelVelocitie...
Definition DifferentialDriveWheelVelocities.hpp:80
constexpr DifferentialDriveWheelVelocities operator+(const DifferentialDriveWheelVelocities &other) const
Adds two DifferentialDriveWheelVelocities and returns the sum.
Definition DifferentialDriveWheelVelocities.hpp:64
constexpr DifferentialDriveWheelVelocities operator-() const
Returns the inverse of the current DifferentialDriveWheelVelocities.
Definition DifferentialDriveWheelVelocities.hpp:92
constexpr DifferentialDriveWheelVelocities operator*(double scalar) const
Multiplies the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWhee...
Definition DifferentialDriveWheelVelocities.hpp:106
wpi::units::meters_per_second_t right
Velocity of the right side of the robot.
Definition DifferentialDriveWheelVelocities.hpp:24
wpi::units::meters_per_second_t left
Velocity of the left side of the robot.
Definition DifferentialDriveWheelVelocities.hpp:19
constexpr DifferentialDriveWheelVelocities operator/(double scalar) const
Divides the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWheelVe...
Definition DifferentialDriveWheelVelocities.hpp:120