WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
MecanumDriveWheelVelocities.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 <algorithm>
8#include <array>
9
10#include "wpi/units/math.hpp"
11#include "wpi/units/velocity.hpp"
13
14namespace wpi::math {
15/**
16 * Represents the wheel velocities for a mecanum drive drivetrain.
17 */
19 /**
20 * Velocity of the front-left wheel.
21 */
22 wpi::units::meters_per_second_t frontLeft = 0_mps;
23
24 /**
25 * Velocity of the front-right wheel.
26 */
27 wpi::units::meters_per_second_t frontRight = 0_mps;
28
29 /**
30 * Velocity of the rear-left wheel.
31 */
32 wpi::units::meters_per_second_t rearLeft = 0_mps;
33
34 /**
35 * Velocity of the rear-right wheel.
36 */
37 wpi::units::meters_per_second_t rearRight = 0_mps;
38
39 /**
40 * Renormalizes the wheel velocities if any individual velocity is above the
41 * specified maximum.
42 *
43 * Sometimes, after inverse kinematics, the requested velocity from one or
44 * more wheels may be above the max attainable velocity for the driving motor
45 * on that wheel. To fix this issue, one can reduce all the wheel velocities
46 * to make sure that all requested module velocities are at-or-below the
47 * absolute threshold, while maintaining the ratio of velocities between
48 * wheels.
49 *
50 * @param attainableMaxVelocity The absolute max velocity that a wheel can
51 * reach.
52 * @return The desaturated MecanumDriveWheelVelocities.
53 */
54 [[nodiscard]]
56 wpi::units::meters_per_second_t attainableMaxVelocity) const {
57 std::array<wpi::units::meters_per_second_t, 4> wheelVelocities{
59 wpi::units::meters_per_second_t realMaxVelocity =
60 wpi::units::math::abs(*std::max_element(
61 wheelVelocities.begin(), wheelVelocities.end(),
62 [](const auto& a, const auto& b) {
63 return wpi::units::math::abs(a) < wpi::units::math::abs(b);
64 }));
65
66 if (realMaxVelocity > attainableMaxVelocity) {
67 for (int i = 0; i < 4; ++i) {
68 wheelVelocities[i] =
69 wheelVelocities[i] / realMaxVelocity * attainableMaxVelocity;
70 }
71 return MecanumDriveWheelVelocities{wheelVelocities[0], wheelVelocities[1],
72 wheelVelocities[2],
73 wheelVelocities[3]};
74 }
75
76 return *this;
77 }
78
79 /**
80 * Adds two MecanumDriveWheelVelocities and returns the sum.
81 *
82 * For example, MecanumDriveWheelVelocities{1.0, 0.5, 2.0, 1.5} +
83 * MecanumDriveWheelVelocities{2.0, 1.5, 0.5, 1.0} =
84 * MecanumDriveWheelVelocities{3.0, 2.0, 2.5, 2.5}
85 *
86 * @param other The MecanumDriveWheelVelocities to add.
87 * @return The sum of the MecanumDriveWheelVelocities.
88 */
90 const MecanumDriveWheelVelocities& other) const {
91 return {frontLeft + other.frontLeft, frontRight + other.frontRight,
92 rearLeft + other.rearLeft, rearRight + other.rearRight};
93 }
94
95 /**
96 * Subtracts the other MecanumDriveWheelVelocities from the current
97 * MecanumDriveWheelVelocities and returns the difference.
98 *
99 * For example, MecanumDriveWheelVelocities{5.0, 4.0, 6.0, 2.5} -
100 * MecanumDriveWheelVelocities{1.0, 2.0, 3.0, 0.5} =
101 * MecanumDriveWheelVelocities{4.0, 2.0, 3.0, 2.0}
102 *
103 * @param other The MecanumDriveWheelVelocities to subtract.
104 * @return The difference between the two MecanumDriveWheelVelocities.
105 */
107 const MecanumDriveWheelVelocities& other) const {
108 return *this + -other;
109 }
110
111 /**
112 * Returns the inverse of the current MecanumDriveWheelVelocities.
113 * This is equivalent to negating all components of the
114 * MecanumDriveWheelVelocities.
115 *
116 * @return The inverse of the current MecanumDriveWheelVelocities.
117 */
119 return {-frontLeft, -frontRight, -rearLeft, -rearRight};
120 }
121
122 /**
123 * Multiplies the MecanumDriveWheelVelocities by a scalar and returns the new
124 * MecanumDriveWheelVelocities.
125 *
126 * For example, MecanumDriveWheelVelocities{2.0, 2.5, 3.0, 3.5} * 2 =
127 * MecanumDriveWheelVelocities{4.0, 5.0, 6.0, 7.0}
128 *
129 * @param scalar The scalar to multiply by.
130 * @return The scaled MecanumDriveWheelVelocities.
131 */
132 constexpr MecanumDriveWheelVelocities operator*(double scalar) const {
133 return {scalar * frontLeft, scalar * frontRight, scalar * rearLeft,
134 scalar * rearRight};
135 }
136
137 /**
138 * Divides the MecanumDriveWheelVelocities by a scalar and returns the new
139 * MecanumDriveWheelVelocities.
140 *
141 * For example, MecanumDriveWheelVelocities{2.0, 2.5, 1.5, 1.0} / 2 =
142 * MecanumDriveWheelVelocities{1.0, 1.25, 0.75, 0.5}
143 *
144 * @param scalar The scalar to divide by.
145 * @return The scaled MecanumDriveWheelVelocities.
146 */
147 constexpr MecanumDriveWheelVelocities operator/(double scalar) const {
148 return operator*(1.0 / scalar);
149 }
150};
151} // namespace wpi::math
152
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Definition LinearSystem.hpp:20
Represents the wheel velocities for a mecanum drive drivetrain.
Definition MecanumDriveWheelVelocities.hpp:18
wpi::units::meters_per_second_t frontRight
Velocity of the front-right wheel.
Definition MecanumDriveWheelVelocities.hpp:27
constexpr MecanumDriveWheelVelocities operator+(const MecanumDriveWheelVelocities &other) const
Adds two MecanumDriveWheelVelocities and returns the sum.
Definition MecanumDriveWheelVelocities.hpp:89
constexpr MecanumDriveWheelVelocities operator-(const MecanumDriveWheelVelocities &other) const
Subtracts the other MecanumDriveWheelVelocities from the current MecanumDriveWheelVelocities and retu...
Definition MecanumDriveWheelVelocities.hpp:106
wpi::units::meters_per_second_t rearLeft
Velocity of the rear-left wheel.
Definition MecanumDriveWheelVelocities.hpp:32
constexpr MecanumDriveWheelVelocities Desaturate(wpi::units::meters_per_second_t attainableMaxVelocity) const
Renormalizes the wheel velocities if any individual velocity is above the specified maximum.
Definition MecanumDriveWheelVelocities.hpp:55
constexpr MecanumDriveWheelVelocities operator/(double scalar) const
Divides the MecanumDriveWheelVelocities by a scalar and returns the new MecanumDriveWheelVelocities.
Definition MecanumDriveWheelVelocities.hpp:147
wpi::units::meters_per_second_t frontLeft
Velocity of the front-left wheel.
Definition MecanumDriveWheelVelocities.hpp:22
constexpr MecanumDriveWheelVelocities operator*(double scalar) const
Multiplies the MecanumDriveWheelVelocities by a scalar and returns the new MecanumDriveWheelVelocitie...
Definition MecanumDriveWheelVelocities.hpp:132
wpi::units::meters_per_second_t rearRight
Velocity of the rear-right wheel.
Definition MecanumDriveWheelVelocities.hpp:37
constexpr MecanumDriveWheelVelocities operator-() const
Returns the inverse of the current MecanumDriveWheelVelocities.
Definition MecanumDriveWheelVelocities.hpp:118