WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
DifferentialDriveWheelVelocities.hpp
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include "wpi/units/math.hpp"
8#include "wpi/units/velocity.hpp"
10
11namespace wpi::math {
12/**
13 * Represents the wheel velocities for a differential drive drivetrain.
14 */
16 /**
17 * Velocity of the left side of the robot.
18 */
19 wpi::units::meters_per_second_t left = 0_mps;
20
21 /**
22 * Velocity of the right side of the robot.
23 */
24 wpi::units::meters_per_second_t right = 0_mps;
25
26 /**
27 * Renormalizes the wheel velocities if either side is above the specified
28 * maximum.
29 *
30 * Sometimes, after inverse kinematics, the requested velocity from one or
31 * more wheels may be above the max attainable velocity for the driving motor
32 * on that wheel. To fix this issue, one can reduce all the wheel velocities
33 * to make sure that all requested module velocities are at-or-below the
34 * absolute threshold, while maintaining the ratio of velocities between
35 * wheels.
36 *
37 * @param attainableMaxVelocity The absolute max velocity that a wheel can
38 * reach.
39 * @return The desaturated DifferentialDriveWheelVelocities.
40 */
41 [[nodiscard]]
43 wpi::units::meters_per_second_t attainableMaxVelocity) {
44 auto realMaxVelocity = wpi::units::math::max(wpi::units::math::abs(left),
45 wpi::units::math::abs(right));
46
47 if (realMaxVelocity > attainableMaxVelocity) {
48 return {left / realMaxVelocity * attainableMaxVelocity,
49 right / realMaxVelocity * attainableMaxVelocity};
50 }
51 return *this;
52 }
53
54 /**
55 * Adds two DifferentialDriveWheelVelocities and returns the sum.
56 *
57 * For example, DifferentialDriveWheelVelocities{1.0, 0.5} +
58 * DifferentialDriveWheelVelocities{2.0, 1.5} =
59 * DifferentialDriveWheelVelocities{3.0, 2.0}
60 *
61 * @param other The DifferentialDriveWheelVelocities to add.
62 * @return The sum of the DifferentialDriveWheelVelocities.
63 */
65 const DifferentialDriveWheelVelocities& other) const {
66 return {left + other.left, right + other.right};
67 }
68
69 /**
70 * Subtracts the other DifferentialDriveWheelVelocities from the current
71 * DifferentialDriveWheelVelocities and returns the difference.
72 *
73 * For example, DifferentialDriveWheelVelocities{5.0, 4.0} -
74 * DifferentialDriveWheelVelocities{1.0, 2.0} =
75 * DifferentialDriveWheelVelocities{4.0, 2.0}
76 *
77 * @param other The DifferentialDriveWheelVelocities to subtract.
78 * @return The difference between the two DifferentialDriveWheelVelocities.
79 */
81 const DifferentialDriveWheelVelocities& other) const {
82 return *this + -other;
83 }
84
85 /**
86 * Returns the inverse of the current DifferentialDriveWheelVelocities.
87 * This is equivalent to negating all components of the
88 * DifferentialDriveWheelVelocities.
89 *
90 * @return The inverse of the current DifferentialDriveWheelVelocities.
91 */
93 return {-left, -right};
94 }
95
96 /**
97 * Multiplies the DifferentialDriveWheelVelocities by a scalar and returns the
98 * new DifferentialDriveWheelVelocities.
99 *
100 * For example, DifferentialDriveWheelVelocities{2.0, 2.5} * 2
101 * = DifferentialDriveWheelVelocities{4.0, 5.0}
102 *
103 * @param scalar The scalar to multiply by.
104 * @return The scaled DifferentialDriveWheelVelocities.
105 */
106 constexpr DifferentialDriveWheelVelocities operator*(double scalar) const {
107 return {scalar * left, scalar * right};
108 }
109
110 /**
111 * Divides the DifferentialDriveWheelVelocities by a scalar and returns the
112 * new DifferentialDriveWheelVelocities.
113 *
114 * For example, DifferentialDriveWheelVelocities{2.0, 2.5} / 2
115 * = DifferentialDriveWheelVelocities{1.0, 1.25}
116 *
117 * @param scalar The scalar to divide by.
118 * @return The scaled DifferentialDriveWheelVelocities.
119 */
120 constexpr DifferentialDriveWheelVelocities operator/(double scalar) const {
121 return operator*(1.0 / scalar);
122 }
123};
124} // namespace wpi::math
125
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Definition LinearSystem.hpp:20
Represents the wheel velocities for a differential drive drivetrain.
Definition DifferentialDriveWheelVelocities.hpp:15
constexpr DifferentialDriveWheelVelocities Desaturate(wpi::units::meters_per_second_t attainableMaxVelocity)
Renormalizes the wheel velocities if either side is above the specified maximum.
Definition DifferentialDriveWheelVelocities.hpp:42
constexpr DifferentialDriveWheelVelocities operator-(const DifferentialDriveWheelVelocities &other) const
Subtracts the other DifferentialDriveWheelVelocities from the current DifferentialDriveWheelVelocitie...
Definition DifferentialDriveWheelVelocities.hpp:80
constexpr DifferentialDriveWheelVelocities operator+(const DifferentialDriveWheelVelocities &other) const
Adds two DifferentialDriveWheelVelocities and returns the sum.
Definition DifferentialDriveWheelVelocities.hpp:64
constexpr DifferentialDriveWheelVelocities operator-() const
Returns the inverse of the current DifferentialDriveWheelVelocities.
Definition DifferentialDriveWheelVelocities.hpp:92
constexpr DifferentialDriveWheelVelocities operator*(double scalar) const
Multiplies the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWhee...
Definition DifferentialDriveWheelVelocities.hpp:106
wpi::units::meters_per_second_t right
Velocity of the right side of the robot.
Definition DifferentialDriveWheelVelocities.hpp:24
wpi::units::meters_per_second_t left
Velocity of the left side of the robot.
Definition DifferentialDriveWheelVelocities.hpp:19
constexpr DifferentialDriveWheelVelocities operator/(double scalar) const
Divides the DifferentialDriveWheelVelocities by a scalar and returns the new DifferentialDriveWheelVe...
Definition DifferentialDriveWheelVelocities.hpp:120