![]() |
WPILibC++ 2027.0.0-alpha-4
|
Represents the wheel velocities for a differential drive drivetrain. More...
#include <wpi/math/kinematics/DifferentialDriveWheelVelocities.hpp>
Public Member Functions | |
| constexpr void | Desaturate (wpi::units::meters_per_second_t attainableMaxVelocity) |
| Renormalizes the wheel velocities if either side is above the specified maximum. | |
| constexpr DifferentialDriveWheelVelocities | operator+ (const DifferentialDriveWheelVelocities &other) const |
| Adds two DifferentialDriveWheelVelocities and returns the sum. | |
| constexpr DifferentialDriveWheelVelocities | operator- (const DifferentialDriveWheelVelocities &other) const |
| Subtracts the other DifferentialDriveWheelVelocities from the current DifferentialDriveWheelVelocities and returns the difference. | |
| constexpr DifferentialDriveWheelVelocities | operator- () const |
| Returns the inverse of the current DifferentialDriveWheelVelocities. | |
| constexpr DifferentialDriveWheelVelocities | operator* (double scalar) const |
| Multiplies the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWheelVelocities. | |
| constexpr DifferentialDriveWheelVelocities | operator/ (double scalar) const |
| Divides the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWheelVelocities. | |
Public Attributes | |
| wpi::units::meters_per_second_t | left = 0_mps |
| Velocity of the left side of the robot. | |
| wpi::units::meters_per_second_t | right = 0_mps |
| Velocity of the right side of the robot. | |
Represents the wheel velocities for a differential drive drivetrain.
|
inlineconstexpr |
Renormalizes the wheel velocities if either side is above the specified maximum.
Sometimes, after inverse kinematics, the requested velocity from one or more wheels may be above the max attainable velocity for the driving motor on that wheel. To fix this issue, one can reduce all the wheel velocities to make sure that all requested module velocities are at-or-below the absolute threshold, while maintaining the ratio of velocities between wheels.
| attainableMaxVelocity | The absolute max velocity that a wheel can reach. |
|
inlineconstexpr |
Multiplies the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWheelVelocities.
For example, DifferentialDriveWheelVelocities{2.0, 2.5} * 2 = DifferentialDriveWheelVelocities{4.0, 5.0}
| scalar | The scalar to multiply by. |
|
inlineconstexpr |
Adds two DifferentialDriveWheelVelocities and returns the sum.
For example, DifferentialDriveWheelVelocities{1.0, 0.5} + DifferentialDriveWheelVelocities{2.0, 1.5} = DifferentialDriveWheelVelocities{3.0, 2.0}
| other | The DifferentialDriveWheelVelocities to add. |
|
inlineconstexpr |
Returns the inverse of the current DifferentialDriveWheelVelocities.
This is equivalent to negating all components of the DifferentialDriveWheelVelocities.
|
inlineconstexpr |
Subtracts the other DifferentialDriveWheelVelocities from the current DifferentialDriveWheelVelocities and returns the difference.
For example, DifferentialDriveWheelVelocities{5.0, 4.0} - DifferentialDriveWheelVelocities{1.0, 2.0} = DifferentialDriveWheelVelocities{4.0, 2.0}
| other | The DifferentialDriveWheelVelocities to subtract. |
|
inlineconstexpr |
Divides the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWheelVelocities.
For example, DifferentialDriveWheelVelocities{2.0, 2.5} / 2 = DifferentialDriveWheelVelocities{1.0, 1.25}
| scalar | The scalar to divide by. |
| wpi::units::meters_per_second_t wpi::math::DifferentialDriveWheelVelocities::left = 0_mps |
Velocity of the left side of the robot.
| wpi::units::meters_per_second_t wpi::math::DifferentialDriveWheelVelocities::right = 0_mps |
Velocity of the right side of the robot.