WPILibC++ 2024.3.2
frc::MecanumDriveWheelSpeeds Struct Reference

Represents the wheel speeds for a mecanum drive drivetrain. More...

#include <frc/kinematics/MecanumDriveWheelSpeeds.h>

Public Member Functions

void Desaturate (units::meters_per_second_t attainableMaxSpeed)
 Renormalizes the wheel speeds if any individual speed is above the specified maximum. More...
 
constexpr MecanumDriveWheelSpeeds operator+ (const MecanumDriveWheelSpeeds &other) const
 Adds two MecanumDriveWheelSpeeds and returns the sum. More...
 
constexpr MecanumDriveWheelSpeeds operator- (const MecanumDriveWheelSpeeds &other) const
 Subtracts the other MecanumDriveWheelSpeeds from the current MecanumDriveWheelSpeeds and returns the difference. More...
 
constexpr MecanumDriveWheelSpeeds operator- () const
 Returns the inverse of the current MecanumDriveWheelSpeeds. More...
 
constexpr MecanumDriveWheelSpeeds operator* (double scalar) const
 Multiplies the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds. More...
 
constexpr MecanumDriveWheelSpeeds operator/ (double scalar) const
 Divides the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds. More...
 

Public Attributes

units::meters_per_second_t frontLeft = 0_mps
 Speed of the front-left wheel. More...
 
units::meters_per_second_t frontRight = 0_mps
 Speed of the front-right wheel. More...
 
units::meters_per_second_t rearLeft = 0_mps
 Speed of the rear-left wheel. More...
 
units::meters_per_second_t rearRight = 0_mps
 Speed of the rear-right wheel. More...
 

Detailed Description

Represents the wheel speeds for a mecanum drive drivetrain.

Member Function Documentation

◆ Desaturate()

void frc::MecanumDriveWheelSpeeds::Desaturate ( units::meters_per_second_t  attainableMaxSpeed)

Renormalizes the wheel speeds if any individual speed is above the specified maximum.

Sometimes, after inverse kinematics, the requested speed from one or more wheels may be above the max attainable speed for the driving motor on that wheel. To fix this issue, one can reduce all the wheel speeds to make sure that all requested module speeds are at-or-below the absolute threshold, while maintaining the ratio of speeds between wheels.

Parameters
attainableMaxSpeedThe absolute max speed that a wheel can reach.

◆ operator*()

constexpr MecanumDriveWheelSpeeds frc::MecanumDriveWheelSpeeds::operator* ( double  scalar) const
inlineconstexpr

Multiplies the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.

For example, MecanumDriveWheelSpeeds{2.0, 2.5, 3.0, 3.5} * 2 = MecanumDriveWheelSpeeds{4.0, 5.0, 6.0, 7.0}

Parameters
scalarThe scalar to multiply by.
Returns
The scaled MecanumDriveWheelSpeeds.

◆ operator+()

constexpr MecanumDriveWheelSpeeds frc::MecanumDriveWheelSpeeds::operator+ ( const MecanumDriveWheelSpeeds other) const
inlineconstexpr

Adds two MecanumDriveWheelSpeeds and returns the sum.

For example, MecanumDriveWheelSpeeds{1.0, 0.5, 2.0, 1.5} + MecanumDriveWheelSpeeds{2.0, 1.5, 0.5, 1.0} = MecanumDriveWheelSpeeds{3.0, 2.0, 2.5, 2.5}

Parameters
otherThe MecanumDriveWheelSpeeds to add.
Returns
The sum of the MecanumDriveWheelSpeeds.

◆ operator-() [1/2]

constexpr MecanumDriveWheelSpeeds frc::MecanumDriveWheelSpeeds::operator- ( ) const
inlineconstexpr

Returns the inverse of the current MecanumDriveWheelSpeeds.

This is equivalent to negating all components of the MecanumDriveWheelSpeeds.

Returns
The inverse of the current MecanumDriveWheelSpeeds.

◆ operator-() [2/2]

constexpr MecanumDriveWheelSpeeds frc::MecanumDriveWheelSpeeds::operator- ( const MecanumDriveWheelSpeeds other) const
inlineconstexpr

Subtracts the other MecanumDriveWheelSpeeds from the current MecanumDriveWheelSpeeds and returns the difference.

For example, MecanumDriveWheelSpeeds{5.0, 4.0, 6.0, 2.5} - MecanumDriveWheelSpeeds{1.0, 2.0, 3.0, 0.5} = MecanumDriveWheelSpeeds{4.0, 2.0, 3.0, 2.0}

Parameters
otherThe MecanumDriveWheelSpeeds to subtract.
Returns
The difference between the two MecanumDriveWheelSpeeds.

◆ operator/()

constexpr MecanumDriveWheelSpeeds frc::MecanumDriveWheelSpeeds::operator/ ( double  scalar) const
inlineconstexpr

Divides the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.

For example, MecanumDriveWheelSpeeds{2.0, 2.5, 1.5, 1.0} / 2 = MecanumDriveWheelSpeeds{1.0, 1.25, 0.75, 0.5}

Parameters
scalarThe scalar to divide by.
Returns
The scaled MecanumDriveWheelSpeeds.

Member Data Documentation

◆ frontLeft

units::meters_per_second_t frc::MecanumDriveWheelSpeeds::frontLeft = 0_mps

Speed of the front-left wheel.

◆ frontRight

units::meters_per_second_t frc::MecanumDriveWheelSpeeds::frontRight = 0_mps

Speed of the front-right wheel.

◆ rearLeft

units::meters_per_second_t frc::MecanumDriveWheelSpeeds::rearLeft = 0_mps

Speed of the rear-left wheel.

◆ rearRight

units::meters_per_second_t frc::MecanumDriveWheelSpeeds::rearRight = 0_mps

Speed of the rear-right wheel.


The documentation for this struct was generated from the following file: