WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::math::MecanumDriveWheelVelocities Struct Reference

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

#include <wpi/math/kinematics/MecanumDriveWheelVelocities.hpp>

Public Member Functions

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

Public Attributes

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

Detailed Description

Represents the wheel velocities for a mecanum drive drivetrain.

Member Function Documentation

◆ Desaturate()

MecanumDriveWheelVelocities wpi::math::MecanumDriveWheelVelocities::Desaturate ( wpi::units::meters_per_second_t attainableMaxVelocity) const
inlineconstexpr

Renormalizes the wheel velocities if any individual velocity 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.

Parameters
attainableMaxVelocityThe absolute max velocity that a wheel can reach.
Returns
Desaturated MecanumDriveWheelVelocities.

◆ operator*()

MecanumDriveWheelVelocities wpi::math::MecanumDriveWheelVelocities::operator* ( double scalar) const
inlineconstexpr

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

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

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

◆ operator+()

MecanumDriveWheelVelocities wpi::math::MecanumDriveWheelVelocities::operator+ ( const MecanumDriveWheelVelocities & other) const
inlineconstexpr

Adds two MecanumDriveWheelVelocities and returns the sum.

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

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

◆ operator-() [1/2]

MecanumDriveWheelVelocities wpi::math::MecanumDriveWheelVelocities::operator- ( ) const
inlineconstexpr

Returns the inverse of the current MecanumDriveWheelVelocities.

This is equivalent to negating all components of the MecanumDriveWheelVelocities.

Returns
The inverse of the current MecanumDriveWheelVelocities.

◆ operator-() [2/2]

MecanumDriveWheelVelocities wpi::math::MecanumDriveWheelVelocities::operator- ( const MecanumDriveWheelVelocities & other) const
inlineconstexpr

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

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

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

◆ operator/()

MecanumDriveWheelVelocities wpi::math::MecanumDriveWheelVelocities::operator/ ( double scalar) const
inlineconstexpr

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

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

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

Member Data Documentation

◆ frontLeft

wpi::units::meters_per_second_t wpi::math::MecanumDriveWheelVelocities::frontLeft = 0_mps

Velocity of the front-left wheel.

◆ frontRight

wpi::units::meters_per_second_t wpi::math::MecanumDriveWheelVelocities::frontRight = 0_mps

Velocity of the front-right wheel.

◆ rearLeft

wpi::units::meters_per_second_t wpi::math::MecanumDriveWheelVelocities::rearLeft = 0_mps

Velocity of the rear-left wheel.

◆ rearRight

wpi::units::meters_per_second_t wpi::math::MecanumDriveWheelVelocities::rearRight = 0_mps

Velocity of the rear-right wheel.


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