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