WPILibC++ 2024.3.2
frc::DifferentialDriveWheelSpeeds Struct Reference

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

#include <frc/kinematics/DifferentialDriveWheelSpeeds.h>

Public Member Functions

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

Public Attributes

units::meters_per_second_t left = 0_mps
 Speed of the left side of the robot. More...
 
units::meters_per_second_t right = 0_mps
 Speed of the right side of the robot. More...
 

Detailed Description

Represents the wheel speeds for a differential drive drivetrain.

Member Function Documentation

◆ Desaturate()

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

Renormalizes the wheel speeds if either side 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 DifferentialDriveWheelSpeeds frc::DifferentialDriveWheelSpeeds::operator* ( double  scalar) const
inlineconstexpr

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

For example, DifferentialDriveWheelSpeeds{2.0, 2.5} * 2 = DifferentialDriveWheelSpeeds{4.0, 5.0}

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

◆ operator+()

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

Adds two DifferentialDriveWheelSpeeds and returns the sum.

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

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

◆ operator-() [1/2]

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

Returns the inverse of the current DifferentialDriveWheelSpeeds.

This is equivalent to negating all components of the DifferentialDriveWheelSpeeds.

Returns
The inverse of the current DifferentialDriveWheelSpeeds.

◆ operator-() [2/2]

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

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

For example, DifferentialDriveWheelSpeeds{5.0, 4.0} - DifferentialDriveWheelSpeeds{1.0, 2.0} = DifferentialDriveWheelSpeeds{4.0, 2.0}

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

◆ operator/()

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

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

For example, DifferentialDriveWheelSpeeds{2.0, 2.5} / 2 = DifferentialDriveWheelSpeeds{1.0, 1.25}

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

Member Data Documentation

◆ left

units::meters_per_second_t frc::DifferentialDriveWheelSpeeds::left = 0_mps

Speed of the left side of the robot.

◆ right

units::meters_per_second_t frc::DifferentialDriveWheelSpeeds::right = 0_mps

Speed of the right side of the robot.


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