WPILibC++ 2024.3.2
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 <wpi/SymbolExports.h>
8
9#include "units/velocity.h"
10
11namespace frc {
12/**
13 * Represents the wheel speeds for a mecanum drive drivetrain.
14 */
16 /**
17 * Speed of the front-left wheel.
18 */
19 units::meters_per_second_t frontLeft = 0_mps;
20
21 /**
22 * Speed of the front-right wheel.
23 */
24 units::meters_per_second_t frontRight = 0_mps;
25
26 /**
27 * Speed of the rear-left wheel.
28 */
29 units::meters_per_second_t rearLeft = 0_mps;
30
31 /**
32 * Speed of the rear-right wheel.
33 */
34 units::meters_per_second_t rearRight = 0_mps;
35
36 /**
37 * Renormalizes the wheel speeds if any individual speed is above the
38 * specified maximum.
39 *
40 * Sometimes, after inverse kinematics, the requested speed from one or
41 * more wheels may be above the max attainable speed for the driving motor on
42 * that wheel. To fix this issue, one can reduce all the wheel speeds to make
43 * sure that all requested module speeds are at-or-below the absolute
44 * threshold, while maintaining the ratio of speeds between wheels.
45 *
46 * @param attainableMaxSpeed The absolute max speed that a wheel can reach.
47 */
48 void Desaturate(units::meters_per_second_t attainableMaxSpeed);
49
50 /**
51 * Adds two MecanumDriveWheelSpeeds and returns the sum.
52 *
53 * <p>For example, MecanumDriveWheelSpeeds{1.0, 0.5, 2.0, 1.5} +
54 * MecanumDriveWheelSpeeds{2.0, 1.5, 0.5, 1.0} =
55 * MecanumDriveWheelSpeeds{3.0, 2.0, 2.5, 2.5}
56 *
57 * @param other The MecanumDriveWheelSpeeds to add.
58 * @return The sum of the MecanumDriveWheelSpeeds.
59 */
61 const MecanumDriveWheelSpeeds& other) const {
62 return {frontLeft + other.frontLeft, frontRight + other.frontRight,
63 rearLeft + other.rearLeft, rearRight + other.rearRight};
64 }
65
66 /**
67 * Subtracts the other MecanumDriveWheelSpeeds from the current
68 * MecanumDriveWheelSpeeds and returns the difference.
69 *
70 * <p>For example, MecanumDriveWheelSpeeds{5.0, 4.0, 6.0, 2.5} -
71 * MecanumDriveWheelSpeeds{1.0, 2.0, 3.0, 0.5} =
72 * MecanumDriveWheelSpeeds{4.0, 2.0, 3.0, 2.0}
73 *
74 * @param other The MecanumDriveWheelSpeeds to subtract.
75 * @return The difference between the two MecanumDriveWheelSpeeds.
76 */
78 const MecanumDriveWheelSpeeds& other) const {
79 return *this + -other;
80 }
81
82 /**
83 * Returns the inverse of the current MecanumDriveWheelSpeeds.
84 * This is equivalent to negating all components of the
85 * MecanumDriveWheelSpeeds.
86 *
87 * @return The inverse of the current MecanumDriveWheelSpeeds.
88 */
90 return {-frontLeft, -frontRight, -rearLeft, -rearRight};
91 }
92
93 /**
94 * Multiplies the MecanumDriveWheelSpeeds by a scalar and returns the new
95 * MecanumDriveWheelSpeeds.
96 *
97 * <p>For example, MecanumDriveWheelSpeeds{2.0, 2.5, 3.0, 3.5} * 2 =
98 * MecanumDriveWheelSpeeds{4.0, 5.0, 6.0, 7.0}
99 *
100 * @param scalar The scalar to multiply by.
101 * @return The scaled MecanumDriveWheelSpeeds.
102 */
103 constexpr MecanumDriveWheelSpeeds operator*(double scalar) const {
104 return {scalar * frontLeft, scalar * frontRight, scalar * rearLeft,
105 scalar * rearRight};
106 }
107
108 /**
109 * Divides the MecanumDriveWheelSpeeds by a scalar and returns the new
110 * MecanumDriveWheelSpeeds.
111 *
112 * <p>For example, MecanumDriveWheelSpeeds{2.0, 2.5, 1.5, 1.0} / 2 =
113 * MecanumDriveWheelSpeeds{1.0, 1.25, 0.75, 0.5}
114 *
115 * @param scalar The scalar to divide by.
116 * @return The scaled MecanumDriveWheelSpeeds.
117 */
118 constexpr MecanumDriveWheelSpeeds operator/(double scalar) const {
119 return operator*(1.0 / scalar);
120 }
121};
122} // namespace frc
123
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Definition: AprilTagPoseEstimator.h:15
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelSpeeds.h:15
constexpr MecanumDriveWheelSpeeds operator-(const MecanumDriveWheelSpeeds &other) const
Subtracts the other MecanumDriveWheelSpeeds from the current MecanumDriveWheelSpeeds and returns the ...
Definition: MecanumDriveWheelSpeeds.h:77
constexpr MecanumDriveWheelSpeeds operator/(double scalar) const
Divides the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.
Definition: MecanumDriveWheelSpeeds.h:118
constexpr MecanumDriveWheelSpeeds operator*(double scalar) const
Multiplies the MecanumDriveWheelSpeeds by a scalar and returns the new MecanumDriveWheelSpeeds.
Definition: MecanumDriveWheelSpeeds.h:103
units::meters_per_second_t frontRight
Speed of the front-right wheel.
Definition: MecanumDriveWheelSpeeds.h:24
constexpr MecanumDriveWheelSpeeds operator-() const
Returns the inverse of the current MecanumDriveWheelSpeeds.
Definition: MecanumDriveWheelSpeeds.h:89
void Desaturate(units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
units::meters_per_second_t frontLeft
Speed of the front-left wheel.
Definition: MecanumDriveWheelSpeeds.h:19
units::meters_per_second_t rearRight
Speed of the rear-right wheel.
Definition: MecanumDriveWheelSpeeds.h:34
units::meters_per_second_t rearLeft
Speed of the rear-left wheel.
Definition: MecanumDriveWheelSpeeds.h:29
constexpr MecanumDriveWheelSpeeds operator+(const MecanumDriveWheelSpeeds &other) const
Adds two MecanumDriveWheelSpeeds and returns the sum.
Definition: MecanumDriveWheelSpeeds.h:60