WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
MecanumDriveWheelAccelerations.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/acceleration.hpp"
9
10namespace wpi::math {
11/**
12 * Represents the wheel accelerations for a mecanum drive drivetrain.
13 */
15 /**
16 * Acceleration of the front-left wheel.
17 */
18 units::meters_per_second_squared_t frontLeft = 0_mps_sq;
19
20 /**
21 * Acceleration of the front-right wheel.
22 */
23 units::meters_per_second_squared_t frontRight = 0_mps_sq;
24
25 /**
26 * Acceleration of the rear-left wheel.
27 */
28 units::meters_per_second_squared_t rearLeft = 0_mps_sq;
29
30 /**
31 * Acceleration of the rear-right wheel.
32 */
33 units::meters_per_second_squared_t rearRight = 0_mps_sq;
34
35 /**
36 * Adds two MecanumDriveWheelAccelerations and returns the sum.
37 *
38 * For example, MecanumDriveWheelAccelerations{1.0, 0.5, 2.0, 1.5} +
39 * MecanumDriveWheelAccelerations{2.0, 1.5, 0.5, 1.0} =
40 * MecanumDriveWheelAccelerations{3.0, 2.0, 2.5, 2.5}
41 *
42 * @param other The MecanumDriveWheelAccelerations to add.
43 * @return The sum of the MecanumDriveWheelAccelerations.
44 */
46 const MecanumDriveWheelAccelerations& other) const {
47 return {frontLeft + other.frontLeft, frontRight + other.frontRight,
48 rearLeft + other.rearLeft, rearRight + other.rearRight};
49 }
50
51 /**
52 * Subtracts the other MecanumDriveWheelAccelerations from the current
53 * MecanumDriveWheelAccelerations and returns the difference.
54 *
55 * For example, MecanumDriveWheelAccelerations{5.0, 4.0, 6.0, 2.5} -
56 * MecanumDriveWheelAccelerations{1.0, 2.0, 3.0, 0.5} =
57 * MecanumDriveWheelAccelerations{4.0, 2.0, 3.0, 2.0}
58 *
59 * @param other The MecanumDriveWheelAccelerations to subtract.
60 * @return The difference between the two MecanumDriveWheelAccelerations.
61 */
63 const MecanumDriveWheelAccelerations& other) const {
64 return *this + -other;
65 }
66
67 /**
68 * Returns the inverse of the current MecanumDriveWheelAccelerations.
69 * This is equivalent to negating all components of the
70 * MecanumDriveWheelAccelerations.
71 *
72 * @return The inverse of the current MecanumDriveWheelAccelerations.
73 */
75 return {-frontLeft, -frontRight, -rearLeft, -rearRight};
76 }
77
78 /**
79 * Multiplies the MecanumDriveWheelAccelerations by a scalar and returns the
80 * new MecanumDriveWheelAccelerations.
81 *
82 * For example, MecanumDriveWheelAccelerations{2.0, 2.5, 3.0, 3.5} * 2 =
83 * MecanumDriveWheelAccelerations{4.0, 5.0, 6.0, 7.0}
84 *
85 * @param scalar The scalar to multiply by.
86 * @return The scaled MecanumDriveWheelAccelerations.
87 */
88 constexpr MecanumDriveWheelAccelerations operator*(double scalar) const {
89 return {scalar * frontLeft, scalar * frontRight, scalar * rearLeft,
90 scalar * rearRight};
91 }
92
93 /**
94 * Divides the MecanumDriveWheelAccelerations by a scalar and returns the new
95 * MecanumDriveWheelAccelerations.
96 *
97 * For example, MecanumDriveWheelAccelerations{2.0, 2.5, 1.5, 1.0} / 2 =
98 * MecanumDriveWheelAccelerations{1.0, 1.25, 0.75, 0.5}
99 *
100 * @param scalar The scalar to divide by.
101 * @return The scaled MecanumDriveWheelAccelerations.
102 */
103 constexpr MecanumDriveWheelAccelerations operator/(double scalar) const {
104 return operator*(1.0 / scalar);
105 }
106
107 /**
108 * Compares two MecanumDriveWheelAccelerations objects.
109 *
110 * @param other The other MecanumDriveWheelAccelerations.
111 *
112 * @return True if the MecanumDriveWheelAccelerations are equal.
113 */
114 constexpr bool operator==(const MecanumDriveWheelAccelerations& other) const =
115 default;
116};
117} // namespace wpi::math
118
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Definition LinearSystem.hpp:20
Represents the wheel accelerations for a mecanum drive drivetrain.
Definition MecanumDriveWheelAccelerations.hpp:14
constexpr MecanumDriveWheelAccelerations operator*(double scalar) const
Multiplies the MecanumDriveWheelAccelerations by a scalar and returns the new MecanumDriveWheelAccele...
Definition MecanumDriveWheelAccelerations.hpp:88
units::meters_per_second_squared_t rearRight
Acceleration of the rear-right wheel.
Definition MecanumDriveWheelAccelerations.hpp:33
constexpr MecanumDriveWheelAccelerations operator+(const MecanumDriveWheelAccelerations &other) const
Adds two MecanumDriveWheelAccelerations and returns the sum.
Definition MecanumDriveWheelAccelerations.hpp:45
units::meters_per_second_squared_t frontRight
Acceleration of the front-right wheel.
Definition MecanumDriveWheelAccelerations.hpp:23
units::meters_per_second_squared_t rearLeft
Acceleration of the rear-left wheel.
Definition MecanumDriveWheelAccelerations.hpp:28
units::meters_per_second_squared_t frontLeft
Acceleration of the front-left wheel.
Definition MecanumDriveWheelAccelerations.hpp:18
constexpr MecanumDriveWheelAccelerations operator-(const MecanumDriveWheelAccelerations &other) const
Subtracts the other MecanumDriveWheelAccelerations from the current MecanumDriveWheelAccelerations an...
Definition MecanumDriveWheelAccelerations.hpp:62
constexpr MecanumDriveWheelAccelerations operator-() const
Returns the inverse of the current MecanumDriveWheelAccelerations.
Definition MecanumDriveWheelAccelerations.hpp:74
constexpr MecanumDriveWheelAccelerations operator/(double scalar) const
Divides the MecanumDriveWheelAccelerations by a scalar and returns the new MecanumDriveWheelAccelerat...
Definition MecanumDriveWheelAccelerations.hpp:103
constexpr bool operator==(const MecanumDriveWheelAccelerations &other) const =default
Compares two MecanumDriveWheelAccelerations objects.