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

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.

Detailed Description

Represents the wheel velocities for a differential drive drivetrain.

Member Function Documentation

◆ Desaturate()

void wpi::math::DifferentialDriveWheelVelocities::Desaturate ( wpi::units::meters_per_second_t attainableMaxVelocity)
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.

Parameters
attainableMaxVelocityThe absolute max velocity that a wheel can reach.

◆ operator*()

DifferentialDriveWheelVelocities wpi::math::DifferentialDriveWheelVelocities::operator* ( double scalar) const
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}

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

◆ operator+()

DifferentialDriveWheelVelocities wpi::math::DifferentialDriveWheelVelocities::operator+ ( const DifferentialDriveWheelVelocities & other) const
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}

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

◆ operator-() [1/2]

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

Returns the inverse of the current DifferentialDriveWheelVelocities.

This is equivalent to negating all components of the DifferentialDriveWheelVelocities.

Returns
The inverse of the current DifferentialDriveWheelVelocities.

◆ operator-() [2/2]

DifferentialDriveWheelVelocities wpi::math::DifferentialDriveWheelVelocities::operator- ( const DifferentialDriveWheelVelocities & other) const
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}

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

◆ operator/()

DifferentialDriveWheelVelocities wpi::math::DifferentialDriveWheelVelocities::operator/ ( double scalar) const
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}

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

Member Data Documentation

◆ left

wpi::units::meters_per_second_t wpi::math::DifferentialDriveWheelVelocities::left = 0_mps

Velocity of the left side of the robot.

◆ right

wpi::units::meters_per_second_t wpi::math::DifferentialDriveWheelVelocities::right = 0_mps

Velocity of the right side of the robot.


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